diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..0d20b64 --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +*.pyc diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 0000000..d89191c --- /dev/null +++ b/.travis.yml @@ -0,0 +1,44 @@ +env: + global: + - secure: Od2ZYUhrfms2EKvWZ+fhiy2aUMKO5v8km9gvRpLs3fQx/Wo23oQwVVx1lNE/bIZ9Uea596d/Y5VnSkZ4r7HRhwyyMw7F2M+5wbW+RIfHN05XaDma3H9ulF94mWQiMrbT9yFur3AeKb+Wwavl6U0bH7/DsFcXLq/z+1GaRNH/Bnc= + +language: python +python: + - "2.6" + - "2.7" + - "3.2" + - "3.3" +script: + # NOTE: we must do all testing on the installed python package, not + # on the build tree. Otherwise the testing is invalid and may not + # indicate the code actually works + # + # Set pythonpath + + # install + - cd pymavlink + - python setup.py build install + - cd .. + + # Generate messages + - mavgen.py --lang='Python' --output=/tmp/ message_definitions/v1.0/common.xml + - mavgen.py --lang='C' --output=/tmp/ message_definitions/v1.0/common.xml + - mavgen.py --lang='CS' --output=/tmp/ message_definitions/v1.0/common.xml + - mavgen.py --lang='WLua' --output=/tmp/ message_definitions/v1.0/common.xml + - mavgen.py --lang='Java' --output=/tmp/ message_definitions/v1.0/common.xml + # Avoid `spurious errors` caused by ~/.npm permission issues + # ref: https://github.com/travis-ci/travis-ci/issues/2244 + # ref: https://github.com/npm/npm/issues/4815 + # Does it already exist? Who owns? What permissions? + - ls -lah ~/.npm || mkdir ~/.npm + # Make sure we own it + # $USER references the current user in Travis env + - sudo chown -R $USER ~/.npm + - "cd pymavlink/generator/javascript && npm test" + + # Test quaternions + - cd $TRAVIS_BUILD_DIR + - pymavlink/tools/quaterniontest.py + +after_success: +- ./scripts/travis_update_generated_repos.sh diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..d2b5f1e --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,117 @@ +project (mavlink NONE) + +# Note: patched version for installation as ROS 3-rd party library +# Provides C-headers and pymavlink + +# settings +cmake_minimum_required (VERSION 2.8.2) +set(PROJECT_VERSION_MAJOR "1") +set(PROJECT_VERSION_MINOR "0") +set(PROJECT_VERSION_PATCH "9") +set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}") +set(PROJECT_CONTACT_EMAIL http://groups.google.com/group/mavlink) +set(PROJECT_CONTACT_VENDOR mavlink) + +include(GNUInstallDirs) + +# hack from urdfdom: by default this would be 'lib/x86_64-linux-gnu' +set(CMAKE_INSTALL_LIBDIR lib) + +# find libraries with cmake modules +set(PythonInterp_FIND_VERSION "2") +find_package(PythonInterp REQUIRED) + +# Try to read package version from package.xml +if(EXISTS ${CMAKE_SOURCE_DIR}/package.xml) + file(WRITE ${CMAKE_BINARY_DIR}/package_version.py + "import re, sys\n" + "from xml.etree import ElementTree as ET\n" + "doc = ET.parse('${CMAKE_SOURCE_DIR}/package.xml')\n" + "ver = doc.find('version').text\n" + "if re.match('\\d+\\.\\d+\\.\\d+', ver):\n" + " sys.stdout.write(ver)\n" + "else:\n" + " sys.stderr.write('Version format error.\\n')\n" + " sys.exit(1)\n" + ) + + execute_process( + COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_BINARY_DIR}/package_version.py + OUTPUT_VARIABLE XML_VERSION + RESULT_VARIABLE XML_RESULT + ) + + string(STRIP "${XML_VERSION}" XML_VERSION) + if(NOT ${XML_RESULT}) + set(PROJECT_VERSION ${XML_VERSION}) + message(STATUS "Package version: ${PROJECT_VERSION}") + else() + message(WARNING "Package version: package.xml parse error, default used: ${PROJECT_VERSION}") + endif() +endif() + +# config files +configure_file(config.h.in config.h) +install(FILES ${CMAKE_BINARY_DIR}/config.h DESTINATION include/${PROJECT_NAME} COMPONENT Dev) + +# mavlink generation +set(mavgen_path ${CMAKE_SOURCE_DIR}/pymavlink/tools/mavgen.py) +set(common_xml_path ${CMAKE_SOURCE_DIR}/message_definitions/v1.0/common.xml) +macro(generateMavlink_v10 definitions) + foreach(definitionAbsPath ${definitions}) + get_filename_component(definition ${definitionAbsPath} NAME_WE) + message(STATUS "processing: ${definitionAbsPath}") + add_custom_command( + OUTPUT include/v1.0/${definition}/${definition}.h + COMMAND /usr/bin/env PYTHONPATH="${CMAKE_SOURCE_DIR}:$ENV{PYTHONPATH}" + ${PYTHON_EXECUTABLE} ${mavgen_path} --lang=C --wire-protocol=1.0 + --output=include/v1.0 ${definitionAbsPath} + DEPENDS ${definitionAbsPath} ${common_xml_path} ${mavgen_path} + ) + add_custom_target(${definition}.xml-v1.0 + ALL DEPENDS include/v1.0/${definition}/${definition}.h + ) + endforeach() +endmacro() + +# build only v1.0 +file(GLOB V10DEFINITIONS ${CMAKE_SOURCE_DIR}/message_definitions/v1.0/*.xml) +generateMavlink_v10("${V10DEFINITIONS}") + +# build pymavlink +add_subdirectory(pymavlink) + +# install files +install(DIRECTORY ${CMAKE_BINARY_DIR}/include/ DESTINATION include/${PROJECT_NAME} COMPONENT Dev FILES_MATCHING PATTERN "*.h*") +install(DIRECTORY ${CMAKE_BINARY_DIR}/src/ DESTINATION share/${PROJECT_NAME} COMPONENT Dev FILES_MATCHING PATTERN "*.c*") +install(DIRECTORY ${CMAKE_SOURCE_DIR}/share/${PROJECT_NAME} DESTINATION share COMPONENT Dev FILES_MATCHING PATTERN "*.c*") + +# thanks for urdfdom project +set(PKG_NAME ${PROJECT_NAME}) +set(PKG_VERSION ${PROJECT_VERSION}) +set(PKG_DESC "MAVLink micro air vehicle marshalling / communication library") +set(PKG_LIBRARIES ) +set(PKG_DEPENDS ) +set(PKG_MAVLINK_DEFINITIONS "${V10DEFINITIONS}") +foreach(def ${V10DEFINITIONS}) + get_filename_component(dialect "${def}" NAME_WE) + list(APPEND PKG_MAVLINK_DIALECTS ${dialect}) +endforeach() + +configure_file(config.cmake.in ${PROJECT_NAME}-config.cmake @ONLY) +install(FILES ${PROJECT_BINARY_DIR}/${PROJECT_NAME}-config.cmake + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/cmake/ COMPONENT cmake) + +configure_file(pc.in ${PROJECT_NAME}.pc @ONLY) +install(FILES ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.pc + DESTINATION ${CMAKE_INSTALL_LIBDIR}/pkgconfig/ COMPONENT pkgconfig) + +# add file extensions and set resource files +configure_file("COPYING" "COPYING.txt" COPYONLY) +install(FILES ${PROJECT_BINARY_DIR}/COPYING.txt + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/ COMPONENT license) + +install(FILES ${CMAKE_SOURCE_DIR}/package.xml + DESTINATION ${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_NAME}/ COMPONENT catkin) + +# vim:sw=4:ts=4:expandtab diff --git a/COPYING b/COPYING new file mode 100644 index 0000000..65c5ca8 --- /dev/null +++ b/COPYING @@ -0,0 +1,165 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + + This version of the GNU Lesser General Public License incorporates +the terms and conditions of version 3 of the GNU General Public +License, supplemented by the additional permissions listed below. + + 0. Additional Definitions. + + As used herein, "this License" refers to version 3 of the GNU Lesser +General Public License, and the "GNU GPL" refers to version 3 of the GNU +General Public License. + + "The Library" refers to a covered work governed by this License, +other than an Application or a Combined Work as defined below. + + An "Application" is any work that makes use of an interface provided +by the Library, but which is not otherwise based on the Library. +Defining a subclass of a class defined by the Library is deemed a mode +of using an interface provided by the Library. + + A "Combined Work" is a work produced by combining or linking an +Application with the Library. The particular version of the Library +with which the Combined Work was made is also called the "Linked +Version". + + The "Minimal Corresponding Source" for a Combined Work means the +Corresponding Source for the Combined Work, excluding any source code +for portions of the Combined Work that, considered in isolation, are +based on the Application, and not on the Linked Version. + + The "Corresponding Application Code" for a Combined Work means the +object code and/or source code for the Application, including any data +and utility programs needed for reproducing the Combined Work from the +Application, but excluding the System Libraries of the Combined Work. + + 1. Exception to Section 3 of the GNU GPL. + + You may convey a covered work under sections 3 and 4 of this License +without being bound by section 3 of the GNU GPL. + + 2. Conveying Modified Versions. + + If you modify a copy of the Library, and, in your modifications, a +facility refers to a function or data to be supplied by an Application +that uses the facility (other than as an argument passed when the +facility is invoked), then you may convey a copy of the modified +version: + + a) under this License, provided that you make a good faith effort to + ensure that, in the event an Application does not supply the + function or data, the facility still operates, and performs + whatever part of its purpose remains meaningful, or + + b) under the GNU GPL, with none of the additional permissions of + this License applicable to that copy. + + 3. Object Code Incorporating Material from Library Header Files. + + The object code form of an Application may incorporate material from +a header file that is part of the Library. You may convey such object +code under terms of your choice, provided that, if the incorporated +material is not limited to numerical parameters, data structure +layouts and accessors, or small macros, inline functions and templates +(ten or fewer lines in length), you do both of the following: + + a) Give prominent notice with each copy of the object code that the + Library is used in it and that the Library and its use are + covered by this License. + + b) Accompany the object code with a copy of the GNU GPL and this license + document. + + 4. Combined Works. + + You may convey a Combined Work under terms of your choice that, +taken together, effectively do not restrict modification of the +portions of the Library contained in the Combined Work and reverse +engineering for debugging such modifications, if you also do each of +the following: + + a) Give prominent notice with each copy of the Combined Work that + the Library is used in it and that the Library and its use are + covered by this License. + + b) Accompany the Combined Work with a copy of the GNU GPL and this license + document. + + c) For a Combined Work that displays copyright notices during + execution, include the copyright notice for the Library among + these notices, as well as a reference directing the user to the + copies of the GNU GPL and this license document. + + d) Do one of the following: + + 0) Convey the Minimal Corresponding Source under the terms of this + License, and the Corresponding Application Code in a form + suitable for, and under terms that permit, the user to + recombine or relink the Application with a modified version of + the Linked Version to produce a modified Combined Work, in the + manner specified by section 6 of the GNU GPL for conveying + Corresponding Source. + + 1) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (a) uses at run time + a copy of the Library already present on the user's computer + system, and (b) will operate properly with a modified version + of the Library that is interface-compatible with the Linked + Version. + + e) Provide Installation Information, but only if you would otherwise + be required to provide such information under section 6 of the + GNU GPL, and only to the extent that such information is + necessary to install and execute a modified version of the + Combined Work produced by recombining or relinking the + Application with a modified version of the Linked Version. (If + you use option 4d0, the Installation Information must accompany + the Minimal Corresponding Source and Corresponding Application + Code. If you use option 4d1, you must provide the Installation + Information in the manner specified by section 6 of the GNU GPL + for conveying Corresponding Source.) + + 5. Combined Libraries. + + You may place library facilities that are a work based on the +Library side by side in a single library together with other library +facilities that are not Applications and are not covered by this +License, and convey such a combined library under terms of your +choice, if you do both of the following: + + a) Accompany the combined library with a copy of the same work based + on the Library, uncombined with any other library facilities, + conveyed under the terms of this License. + + b) Give prominent notice with the combined library that part of it + is a work based on the Library, and explaining where to find the + accompanying uncombined form of the same work. + + 6. Revised Versions of the GNU Lesser General Public License. + + The Free Software Foundation may publish revised and/or new versions +of the GNU Lesser General Public License from time to time. Such new +versions will be similar in spirit to the present version, but may +differ in detail to address new problems or concerns. + + Each version is given a distinguishing version number. If the +Library as you received it specifies that a certain numbered version +of the GNU Lesser General Public License "or any later version" +applies to it, you have the option of following the terms and +conditions either of that published version or of any later version +published by the Free Software Foundation. If the Library as you +received it does not specify a version number of the GNU Lesser +General Public License, you may choose any version of the GNU Lesser +General Public License ever published by the Free Software Foundation. + + If the Library as you received it specifies that a proxy can decide +whether future versions of the GNU Lesser General Public License shall +apply, that proxy's public statement of acceptance of any version is +permanent authorization for you to choose that version for the +Library. diff --git a/README.md b/README.md new file mode 100644 index 0000000..f45aba6 --- /dev/null +++ b/README.md @@ -0,0 +1,100 @@ +[![Build Status](https://travis-ci.org/mavlink/mavlink.svg?branch=master)](https://travis-ci.org/mavlink/mavlink) + +## MAVLink ## + +* Official Website: http://mavlink.org +* Source: [Mavlink Generator](https://github.com/mavlink/mavlink) +* Binaries (always up-to-date from master): + * [C/C++ header-only library](https://github.com/mavlink/c_library) +* Mailing list: [Google Groups](http://groups.google.com/group/mavlink) + +MAVLink -- Micro Air Vehicle Message Marshalling Library. + +This is a library for lightweight communication between Micro Air Vehicles (swarm) and/or ground control stations. It allows for defining messages within XML files, which then are converted into appropriate source code for different languages. These XML files are called dialects, most of which build on the *common* dialect provided in `common.xml`. + +The MAVLink protocol performs byte-level serialization and so is appropriate for use with any type of radio modem. + +This repository is largely Python scripts that convert XML files into language-specific libraries. There are additional Python scripts providing examples and utilities for working with MAVLink data. These scripts, as well as the generated Python code for MAVLink dialects, require Python 2.7 or greater. + +Note that there are two incompatible versions of the MAVLink protocol: v0.9 and v1.0. Most programs, including [QGroundControl](https://github.com/mavlink/qgroundcontrol), have switched over to v1.0. The v0.9 protocol is **DEPRECATED** and should only be used to maintain backwards compatibility where necessary. + +### Requirements ### + * Python 2.7+ + * Tkinter (if GUI functionality is desired) + +### Installation ### + 1. Clone into a user-writable directory. + 2. Add the repository directory to your `PYTHONPATH` + 3. Generate MAVLink parser files following the instructions in the next section *AND/OR* run included helper scripts described in the Scripts/Examples secion. + +### Generating Language-specific Source Files ### + +Language-specific files can be generated via a Python script from the command line or using a GUI. If a dialect XML file has a dependency on another XML file, they must be located in the same directory. Since most MAVLink dialects depend on the **common** messageset, it is recommend that you place your dialect with the others in `/message_definitions/v1.0/`. + +Available languages are: + + * C + * C# + * Java + * JavaScript + * Lua + * Python, version 2.7+ + +#### From a GUI (recommended) #### + +mavgenerate.py is a header generation tool GUI written in Python. It requires Tkinter, which is only included with Python on Windows, so it will need to be installed separately on non-Windows platforms. It can be run from anywhere using Python's -m argument: + + $ python -m mavgenerate + +#### From the command line #### + +mavgen.py is a command-line interface for generating a language-specific MAVLink library. This is actually the backend used by `mavgenerate.py`. After the `mavlink` directory has been added to the Python path, it can be run by executing from the command line: + + $ python -m pymavlink.tools.mavgen + +### Usage ### + +Using the generated MAVLink dialect libraries varies depending on the language, with language-specific details below: + +#### C #### +To use MAVLink, include the *mavlink.h* header file in your project: + + #include + +Do not include the individual message files. In some cases you will have to add the main folder to the include search path as well. To be safe, we recommend these flags: + + $ gcc -I mavlink/include -I mavlink/include/ + +The C MAVLink library utilizes a channels metaphor to allow for simultaneous processing of multiple MAVLink streams in the same program. It is therefore important to use the correct channel for each operation as all receiving and transmitting functions provided by MAVLink require a channel. If only one MAVLink stream exists, channel 0 should be used by using the `MAVLINK_COMM_0` constant. + +##### Receiving ###### +MAVLink reception is then done using `mavlink_helpers.h:mavlink_parse_char()`. + +##### Transmitting ##### +Transmitting can be done by using the `mavlink_msg_*_pack()` function, where one is defined for every message. The packed message can then be serialized with `mavlink_helpers.h:mavlink_msg_to_send_buffer()` and then writing the resultant byte array out over the appropriate serial interface. + +It is possible to simplify the above by writing wrappers around the transmitting/receiving code. A multi-byte writing macro can be defined, `MAVLINK_SEND_UART_BYTES()`, or a single-byte function can be defined, `comm_send_ch()`, that wrap the low-level driver for transmitting the data. If this is done, `MAVLINK_USE_CONVENIENCE_FUNCTIONS` must be defined. + +### Scripts/Examples ### +This MAVLink library also comes with supporting libraries and scripts for using, manipulating, and parsing MAVLink streams within the pymavlink, pymav +link/tools, and pymavlink/examples directories. + +The scripts have the following requirements: + * Python 2.7+ + * mavlink repository folder in `PYTHONPATH` + * Write access to the entire `mavlink` folder. + * Your dialect's XML file is in `message_definitions/*/` + +Running these scripts can be done by running Python with the '-m' switch, which indicates that the given script exists on the PYTHONPATH. This is the proper way to run Python scripts that are part of a library as per PEP-328 (and the rejected PEP-3122). The following code runs `mavlogdump.py` in `/pymavlink/tools/` on the recorded MAVLink stream `test_run.mavlink` (other scripts in `/tools` and `/scripts` can be run in a similar fashion): + + $ python -m pymavlink.tools.mavlogdump test_run.mavlink + +### License ### + +MAVLink is licensed under the terms of the Lesser General Public License (version 3) of the Free Software Foundation (LGPLv3). The C-language version of MAVLink is a header-only library, and as such compiling an application with it is considered "using the library", not a derived work. MAVLink can therefore be used without limits in any closed-source application without publishing the source code of the closed-source application. + +See the *COPYING* file for more info. + +### Credits ### + +© 2009-2014 [Lorenz Meier](mailto:mail@qgroundcontrol.org) diff --git a/README.md.save b/README.md.save new file mode 100644 index 0000000..5c10e4a --- /dev/null +++ b/README.md.save @@ -0,0 +1,101 @@ +ls +[![Build Status](https://travis-ci.org/mavlink/mavlink.svg?branch=master)](https://travis-ci.org/mavlink/mavlink) + +## MAVLink ## + +* Official Website: http://mavlink.org +* Source: [Mavlink Generator](https://github.com/mavlink/mavlink) +* Binaries (always up-to-date from master): + * [C/C++ header-only library](https://github.com/mavlink/c_library) +* Mailing list: [Google Groups](http://groups.google.com/group/mavlink) + +MAVLink -- Micro Air Vehicle Message Marshalling Library. + +This is a library for lightweight communication between Micro Air Vehicles (swarm) and/or ground control stations. It allows for defining messages within XML files, which then are converted into appropriate source code for different languages. These XML files are called dialects, most of which build on the *common* dialect provided in `common.xml`. + +The MAVLink protocol performs byte-level serialization and so is appropriate for use with any type of radio modem. + +This repository is largely Python scripts that convert XML files into language-specific libraries. There are additional Python scripts providing examples and utilities for working with MAVLink data. These scripts, as well as the generated Python code for MAVLink dialects, require Python 2.7 or greater. + +Note that there are two incompatible versions of the MAVLink protocol: v0.9 and v1.0. Most programs, including [QGroundControl](https://github.com/mavlink/qgroundcontrol), have switched over to v1.0. The v0.9 protocol is **DEPRECATED** and should only be used to maintain backwards compatibility where necessary. + +### Requirements ### + * Python 2.7+ + * Tkinter (if GUI functionality is desired) + +### Installation ### + 1. Clone into a user-writable directory. + 2. Add the repository directory to your `PYTHONPATH` + 3. Generate MAVLink parser files following the instructions in the next section *AND/OR* run included helper scripts described in the Scripts/Examples secion. + +### Generating Language-specific Source Files ### + +Language-specific files can be generated via a Python script from the command line or using a GUI. If a dialect XML file has a dependency on another XML file, they must be located in the same directory. Since most MAVLink dialects depend on the **common** messageset, it is recommend that you place your dialect with the others in `/message_definitions/v1.0/`. + +Available languages are: + + * C + * C# + * Java + * JavaScript + * Lua + * Python, version 2.7+ + +#### From a GUI (recommended) #### + +mavgenerate.py is a header generation tool GUI written in Python. It requires Tkinter, which is only included with Python on Windows, so it will need to be installed separately on non-Windows platforms. It can be run from anywhere using Python's -m argument: + + $ python -m mavgenerate + +#### From the command line #### + +mavgen.py is a command-line interface for generating a language-specific MAVLink library. This is actually the backend used by `mavgenerate.py`. After the `mavlink` directory has been added to the Python path, it can be run by executing from the command line: + + $ python -m pymavlink.tools.mavgen + +### Usage ### + +Using the generated MAVLink dialect libraries varies depending on the language, with language-specific details below: + +#### C #### +To use MAVLink, include the *mavlink.h* header file in your project: + + #include + +Do not include the individual message files. In some cases you will have to add the main folder to the include search path as well. To be safe, we recommend these flags: + + $ gcc -I mavlink/include -I mavlink/include/ + +The C MAVLink library utilizes a channels metaphor to allow for simultaneous processing of multiple MAVLink streams in the same program. It is therefore important to use the correct channel for each operation as all receiving and transmitting functions provided by MAVLink require a channel. If only one MAVLink stream exists, channel 0 should be used by using the `MAVLINK_COMM_0` constant. + +##### Receiving ###### +MAVLink reception is then done using `mavlink_helpers.h:mavlink_parse_char()`. + +##### Transmitting ##### +Transmitting can be done by using the `mavlink_msg_*_pack()` function, where one is defined for every message. The packed message can then be serialized with `mavlink_helpers.h:mavlink_msg_to_send_buffer()` and then writing the resultant byte array out over the appropriate serial interface. + +It is possible to simplify the above by writing wrappers around the transmitting/receiving code. A multi-byte writing macro can be defined, `MAVLINK_SEND_UART_BYTES()`, or a single-byte function can be defined, `comm_send_ch()`, that wrap the low-level driver for transmitting the data. If this is done, `MAVLINK_USE_CONVENIENCE_FUNCTIONS` must be defined. + +### Scripts/Examples ### +This MAVLink library also comes with supporting libraries and scripts for using, manipulating, and parsing MAVLink streams within the pymavlink, pymav +link/tools, and pymavlink/examples directories. + +The scripts have the following requirements: + * Python 2.7+ + * mavlink repository folder in `PYTHONPATH` + * Write access to the entire `mavlink` folder. + * Your dialect's XML file is in `message_definitions/*/` + +Running these scripts can be done by running Python with the '-m' switch, which indicates that the given script exists on the PYTHONPATH. This is the proper way to run Python scripts that are part of a library as per PEP-328 (and the rejected PEP-3122). The following code runs `mavlogdump.py` in `/pymavlink/tools/` on the recorded MAVLink stream `test_run.mavlink` (other scripts in `/tools` and `/scripts` can be run in a similar fashion): + + $ python -m pymavlink.tools.mavlogdump test_run.mavlink + +### License ### + +MAVLink is licensed under the terms of the Lesser General Public License (version 3) of the Free Software Foundation (LGPLv3). The C-language version of MAVLink is a header-only library, and as such compiling an application with it is considered "using the library", not a derived work. MAVLink can therefore be used without limits in any closed-source application without publishing the source code of the closed-source application. + +See the *COPYING* file for more info. + +### Credits ### + +© 2009-2014 [Lorenz Meier](mailto:mail@qgroundcontrol.org) diff --git a/cmake/WELCOME.txt b/cmake/WELCOME.txt new file mode 100644 index 0000000..5330087 --- /dev/null +++ b/cmake/WELCOME.txt @@ -0,0 +1 @@ +Welcome to installation. This program will guide you through the installation of this software. diff --git a/cmake/arkcmake/DefineCMakeDefaults.cmake b/cmake/arkcmake/DefineCMakeDefaults.cmake new file mode 100644 index 0000000..1ea2fd8 --- /dev/null +++ b/cmake/arkcmake/DefineCMakeDefaults.cmake @@ -0,0 +1,32 @@ +# 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.") diff --git a/cmake/arkcmake/DefineCompilerFlags.cmake b/cmake/arkcmake/DefineCompilerFlags.cmake new file mode 100644 index 0000000..0926328 --- /dev/null +++ b/cmake/arkcmake/DefineCompilerFlags.cmake @@ -0,0 +1,90 @@ +# 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) diff --git a/cmake/arkcmake/ExternalProjectWithFilename.cmake b/cmake/arkcmake/ExternalProjectWithFilename.cmake new file mode 100644 index 0000000..b4ca674 --- /dev/null +++ b/cmake/arkcmake/ExternalProjectWithFilename.cmake @@ -0,0 +1,1497 @@ +# - Create custom targets to build projects in external trees +# The 'ExternalProjectWithFilename_Add' function creates a custom target to drive +# download, update/patch, configure, build, install and test steps of an +# external project: +# ExternalProjectWithFilename_Add( # Name for custom target +# [DEPENDS projects...] # Targets on which the project depends +# [PREFIX dir] # Root dir for entire project +# [LIST_SEPARATOR sep] # Sep to be replaced by ; in cmd lines +# [TMP_DIR dir] # Directory to store temporary files +# [STAMP_DIR dir] # Directory to store step timestamps +# #--Download step-------------- +# [FILENAME filename] # Set the download filename +# [DOWNLOAD_DIR dir] # Directory to store downloaded files +# [DOWNLOAD_COMMAND cmd...] # Command to download source tree +# [CVS_REPOSITORY cvsroot] # CVSROOT of CVS repository +# [CVS_MODULE mod] # Module to checkout from CVS repo +# [CVS_TAG tag] # Tag to checkout from CVS repo +# [SVN_REPOSITORY url] # URL of Subversion repo +# [SVN_REVISION rev] # Revision to checkout from Subversion repo +# [SVN_USERNAME john ] # Username for Subversion checkout and update +# [SVN_PASSWORD doe ] # Password for Subversion checkout and update +# [SVN_TRUST_CERT 1 ] # Trust the Subversion server site certificate +# [GIT_REPOSITORY url] # URL of git repo +# [GIT_TAG tag] # Git branch name, commit id or tag +# [URL /.../src.tgz] # Full path or URL of source +# [URL_MD5 md5] # MD5 checksum of file at URL +# [TIMEOUT seconds] # Time allowed for file download operations +# #--Update/Patch step---------- +# [UPDATE_COMMAND cmd...] # Source work-tree update command +# [PATCH_COMMAND cmd...] # Command to patch downloaded source +# #--Configure step------------- +# [SOURCE_DIR dir] # Source dir to be used for build +# [CONFIGURE_COMMAND cmd...] # Build tree configuration command +# [CMAKE_COMMAND /.../cmake] # Specify alternative cmake executable +# [CMAKE_GENERATOR gen] # Specify generator for native build +# [CMAKE_ARGS args...] # Arguments to CMake command line +# [CMAKE_CACHE_ARGS args...] # Initial cache arguments, of the form -Dvar:string=on +# #--Build step----------------- +# [BINARY_DIR dir] # Specify build dir location +# [BUILD_COMMAND cmd...] # Command to drive the native build +# [BUILD_IN_SOURCE 1] # Use source dir for build dir +# #--Install step--------------- +# [INSTALL_DIR dir] # Installation prefix +# [INSTALL_COMMAND cmd...] # Command to drive install after build +# #--Test step------------------ +# [TEST_BEFORE_INSTALL 1] # Add test step executed before install step +# [TEST_AFTER_INSTALL 1] # Add test step executed after install step +# [TEST_COMMAND cmd...] # Command to drive test +# #--Output logging------------- +# [LOG_DOWNLOAD 1] # Wrap download in script to log output +# [LOG_UPDATE 1] # Wrap update in script to log output +# [LOG_CONFIGURE 1] # Wrap configure in script to log output +# [LOG_BUILD 1] # Wrap build in script to log output +# [LOG_TEST 1] # Wrap test in script to log output +# [LOG_INSTALL 1] # Wrap install in script to log output +# #--Custom targets------------- +# [STEP_TARGETS st1 st2 ...] # Generate custom targets for these steps +# ) +# The *_DIR options specify directories for the project, with default +# directories computed as follows. +# If the PREFIX option is given to ExternalProjectWithFilename_Add() or the EP_PREFIX +# directory property is set, then an external project is built and installed +# under the specified prefix: +# TMP_DIR = /tmp +# STAMP_DIR = /src/-stamp +# DOWNLOAD_DIR = /src +# SOURCE_DIR = /src/ +# BINARY_DIR = /src/-build +# INSTALL_DIR = +# Otherwise, if the EP_BASE directory property is set then components +# of an external project are stored under the specified base: +# TMP_DIR = /tmp/ +# STAMP_DIR = /Stamp/ +# DOWNLOAD_DIR = /Download/ +# SOURCE_DIR = /Source/ +# BINARY_DIR = /Build/ +# INSTALL_DIR = /Install/ +# If no PREFIX, EP_PREFIX, or EP_BASE is specified then the default +# is to set PREFIX to "-prefix". +# Relative paths are interpreted with respect to the build directory +# corresponding to the source directory in which ExternalProjectWithFilename_Add is +# invoked. +# +# If SOURCE_DIR is explicitly set to an existing directory the project +# will be built from it. +# Otherwise a download step must be specified using one of the +# DOWNLOAD_COMMAND, CVS_*, SVN_*, or URL options. +# The URL option may refer locally to a directory or source tarball, +# or refer to a remote tarball (e.g. http://.../src.tgz). +# +# The 'ExternalProjectWithFilename_Add_Step' function adds a custom step to an external +# project: +# ExternalProjectWithFilename_Add_Step( # Names of project and custom step +# [COMMAND cmd...] # Command line invoked by this step +# [COMMENT "text..."] # Text printed when step executes +# [DEPENDEES steps...] # Steps on which this step depends +# [DEPENDERS steps...] # Steps that depend on this step +# [DEPENDS files...] # Files on which this step depends +# [ALWAYS 1] # No stamp file, step always runs +# [WORKING_DIRECTORY dir] # Working directory for command +# [LOG 1] # Wrap step in script to log output +# ) +# The command line, comment, and working directory of every standard +# and custom step is processed to replace tokens +# , +# , +# , +# and +# with corresponding property values. +# +# The 'ExternalProjectWithFilename_Get_Property' function retrieves external project +# target properties: +# ExternalProjectWithFilename_Get_Property( [prop1 [prop2 [...]]]) +# It stores property values in variables of the same name. +# Property names correspond to the keyword argument names of +# 'ExternalProjectWithFilename_Add'. +# +# The 'ExternalProjectWithFilename_Add_StepTargets' function generates custom targets for +# the steps listed: +# ExternalProjectWithFilename_Add_StepTargets( [step1 [step2 [...]]]) +# +# If STEP_TARGETS is set then ExternalProjectWithFilename_Add_StepTargets is automatically +# called at the end of matching calls to ExternalProjectWithFilename_Add_Step. Pass +# STEP_TARGETS explicitly to individual ExternalProjectWithFilename_Add calls, or +# implicitly to all ExternalProjectWithFilename_Add calls by setting the directory property +# EP_STEP_TARGETS. +# +# If STEP_TARGETS is not set, clients may still manually call +# ExternalProjectWithFilename_Add_StepTargets after calling ExternalProjectWithFilename_Add or +# ExternalProjectWithFilename_Add_Step. +# +# This functionality is provided to make it easy to drive the steps +# independently of each other by specifying targets on build command lines. +# For example, you may be submitting to a sub-project based dashboard, where +# you want to drive the configure portion of the build, then submit to the +# dashboard, followed by the build portion, followed by tests. If you invoke +# a custom target that depends on a step halfway through the step dependency +# chain, then all the previous steps will also run to ensure everything is +# up to date. +# +# For example, to drive configure, build and test steps independently for each +# ExternalProjectWithFilename_Add call in your project, write the following line prior to +# any ExternalProjectWithFilename_Add calls in your CMakeLists file: +# +# set_property(DIRECTORY PROPERTY EP_STEP_TARGETS configure build test) + +#============================================================================= +# Copyright 2008-2009 Kitware, Inc. +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of CMake, substitute the full +# License text for the above reference.) + +# Pre-compute a regex to match documented keywords for each command. +math(EXPR _ep_documentation_line_count "${CMAKE_CURRENT_LIST_LINE} - 16") +file(STRINGS "${CMAKE_CURRENT_LIST_FILE}" lines + LIMIT_COUNT ${_ep_documentation_line_count} + REGEX "^# ( \\[[A-Z0-9_]+ [^]]*\\] +#.*$|[A-Za-z0-9_]+\\()") +foreach(line IN LISTS lines) + if("${line}" MATCHES "^# [A-Za-z0-9_]+\\(") + if(_ep_func) + set(_ep_keywords_${_ep_func} "${_ep_keywords_${_ep_func}})$") + endif() + string(REGEX REPLACE "^# ([A-Za-z0-9_]+)\\(.*" "\\1" _ep_func "${line}") + #message("function [${_ep_func}]") + set(_ep_keywords_${_ep_func} "^(") + set(_ep_keyword_sep) + else() + string(REGEX REPLACE "^# \\[([A-Z0-9_]+) .*" "\\1" _ep_key "${line}") + #message(" keyword [${_ep_key}]") + set(_ep_keywords_${_ep_func} + "${_ep_keywords_${_ep_func}}${_ep_keyword_sep}${_ep_key}") + set(_ep_keyword_sep "|") + endif() +endforeach() +if(_ep_func) + set(_ep_keywords_${_ep_func} "${_ep_keywords_${_ep_func}})$") +endif() + + +function(_ep_parse_arguments f name ns args) + # Transfer the arguments to this function into target properties for the + # new custom target we just added so that we can set up all the build steps + # correctly based on target properties. + # + # We loop through ARGN and consider the namespace starting with an + # upper-case letter followed by at least two more upper-case letters, + # numbers or underscores to be keywords. + set(key) + + foreach(arg IN LISTS args) + set(is_value 1) + + if(arg MATCHES "^[A-Z][A-Z0-9_][A-Z0-9_]+$" AND + NOT ((arg STREQUAL "${key}") AND (key STREQUAL "COMMAND")) AND + NOT arg MATCHES "^(TRUE|FALSE)$") + if(_ep_keywords_${f} AND arg MATCHES "${_ep_keywords_${f}}") + set(is_value 0) + endif() + endif() + + if(is_value) + if(key) + # Value + if(NOT arg STREQUAL "") + set_property(TARGET ${name} APPEND PROPERTY ${ns}${key} "${arg}") + else() + get_property(have_key TARGET ${name} PROPERTY ${ns}${key} SET) + if(have_key) + get_property(value TARGET ${name} PROPERTY ${ns}${key}) + set_property(TARGET ${name} PROPERTY ${ns}${key} "${value};${arg}") + else() + set_property(TARGET ${name} PROPERTY ${ns}${key} "${arg}") + endif() + endif() + else() + # Missing Keyword + message(AUTHOR_WARNING "value '${arg}' with no previous keyword in ${f}") + endif() + else() + set(key "${arg}") + endif() + endforeach() +endfunction(_ep_parse_arguments) + + +define_property(DIRECTORY PROPERTY "EP_BASE" INHERITED + BRIEF_DOCS "Base directory for External Project storage." + FULL_DOCS + "See documentation of the ExternalProjectWithFilename_Add() function in the " + "ExternalProjectWithFilename module." + ) + +define_property(DIRECTORY PROPERTY "EP_PREFIX" INHERITED + BRIEF_DOCS "Top prefix for External Project storage." + FULL_DOCS + "See documentation of the ExternalProjectWithFilename_Add() function in the " + "ExternalProjectWithFilename module." + ) + +define_property(DIRECTORY PROPERTY "EP_STEP_TARGETS" INHERITED + BRIEF_DOCS + "List of ExternalProjectWithFilename steps that automatically get corresponding targets" + FULL_DOCS + "See documentation of the ExternalProjectWithFilename_Add_StepTargets() function in the " + "ExternalProjectWithFilename module." + ) + + +function(_ep_write_gitclone_script script_filename source_dir git_EXECUTABLE git_repository git_tag src_name work_dir) + file(WRITE ${script_filename} +"if(\"${git_tag}\" STREQUAL \"\") + message(FATAL_ERROR \"Tag for git checkout should not be empty.\") +endif() + +execute_process( + COMMAND \${CMAKE_COMMAND} -E remove_directory \"${source_dir}\" + RESULT_VARIABLE error_code + ) +if(error_code) + message(FATAL_ERROR \"Failed to remove directory: '${source_dir}'\") +endif() + +execute_process( + COMMAND \"${git_EXECUTABLE}\" clone \"${git_repository}\" \"${src_name}\" + WORKING_DIRECTORY \"${work_dir}\" + RESULT_VARIABLE error_code + ) +if(error_code) + message(FATAL_ERROR \"Failed to clone repository: '${git_repository}'\") +endif() + +execute_process( + COMMAND \"${git_EXECUTABLE}\" checkout ${git_tag} + WORKING_DIRECTORY \"${work_dir}/${src_name}\" + RESULT_VARIABLE error_code + ) +if(error_code) + message(FATAL_ERROR \"Failed to checkout tag: '${git_tag}'\") +endif() + +execute_process( + COMMAND \"${git_EXECUTABLE}\" submodule init + WORKING_DIRECTORY \"${work_dir}/${src_name}\" + RESULT_VARIABLE error_code + ) +if(error_code) + message(FATAL_ERROR \"Failed to init submodules in: '${work_dir}/${src_name}'\") +endif() + +execute_process( + COMMAND \"${git_EXECUTABLE}\" submodule update --recursive + WORKING_DIRECTORY \"${work_dir}/${src_name}\" + RESULT_VARIABLE error_code + ) +if(error_code) + message(FATAL_ERROR \"Failed to update submodules in: '${work_dir}/${src_name}'\") +endif() + +" +) + +endfunction(_ep_write_gitclone_script) + + +function(_ep_write_downloadfile_script script_filename remote local timeout md5) + if(timeout) + set(timeout_args TIMEOUT ${timeout}) + set(timeout_msg "${timeout} seconds") + else() + set(timeout_args "# no TIMEOUT") + set(timeout_msg "none") + endif() + + if(md5) + set(md5_args EXPECTED_MD5 ${md5}) + else() + set(md5_args "# no EXPECTED_MD5") + endif() + + file(WRITE ${script_filename} +"message(STATUS \"downloading... + src='${remote}' + dst='${local}' + timeout='${timeout_msg}'\") + +file(DOWNLOAD + \"${remote}\" + \"${local}\" + SHOW_PROGRESS + ${md5_args} + ${timeout_args} + STATUS status + LOG log) + +list(GET status 0 status_code) +list(GET status 1 status_string) + +if(NOT status_code EQUAL 0) + message(FATAL_ERROR \"error: downloading '${remote}' failed + status_code: \${status_code} + status_string: \${status_string} + log: \${log} +\") +endif() + +message(STATUS \"downloading... done\") +" +) + +endfunction(_ep_write_downloadfile_script) + + +function(_ep_write_verifyfile_script script_filename local md5) + file(WRITE ${script_filename} +"message(STATUS \"verifying file... + file='${local}'\") + +set(verified 0) + +# If an expected md5 checksum exists, compare against it: +# +if(NOT \"${md5}\" STREQUAL \"\") + execute_process(COMMAND \${CMAKE_COMMAND} -E md5sum \"${local}\" + OUTPUT_VARIABLE ov + OUTPUT_STRIP_TRAILING_WHITESPACE + RESULT_VARIABLE rv) + + if(NOT rv EQUAL 0) + message(FATAL_ERROR \"error: computing md5sum of '${local}' failed\") + endif() + + string(REGEX MATCH \"^([0-9A-Fa-f]+)\" md5_actual \"\${ov}\") + + string(TOLOWER \"\${md5_actual}\" md5_actual) + string(TOLOWER \"${md5}\" md5) + + if(NOT \"\${md5}\" STREQUAL \"\${md5_actual}\") + message(FATAL_ERROR \"error: md5sum of '${local}' does not match expected value + md5_expected: \${md5} + md5_actual: \${md5_actual} +\") + endif() + + set(verified 1) +endif() + +if(verified) + message(STATUS \"verifying file... done\") +else() + message(STATUS \"verifying file... warning: did not verify file - no URL_MD5 checksum argument? corrupt file?\") +endif() +" +) + +endfunction(_ep_write_verifyfile_script) + + +function(_ep_write_extractfile_script script_filename name filename directory) + set(args "") + + if(filename MATCHES "(\\.|=)(bz2|tar\\.gz|tgz|zip)$") + set(args xfz) + endif() + + if(filename MATCHES "(\\.|=)tar$") + set(args xf) + endif() + + if(args STREQUAL "") + message(SEND_ERROR "error: do not know how to extract '${filename}' -- known types are .bz2, .tar, .tar.gz, .tgz and .zip") + return() + endif() + + file(WRITE ${script_filename} +"# Make file names absolute: +# +get_filename_component(filename \"${filename}\" ABSOLUTE) +get_filename_component(directory \"${directory}\" ABSOLUTE) + +message(STATUS \"extracting... + src='\${filename}' + dst='\${directory}'\") + +if(NOT EXISTS \"\${filename}\") + message(FATAL_ERROR \"error: file to extract does not exist: '\${filename}'\") +endif() + +# Prepare a space for extracting: +# +set(i 1234) +while(EXISTS \"\${directory}/../ex-${name}\${i}\") + math(EXPR i \"\${i} + 1\") +endwhile() +set(ut_dir \"\${directory}/../ex-${name}\${i}\") +file(MAKE_DIRECTORY \"\${ut_dir}\") + +# Extract it: +# +message(STATUS \"extracting... [tar ${args}]\") +execute_process(COMMAND \${CMAKE_COMMAND} -E tar ${args} \${filename} + WORKING_DIRECTORY \${ut_dir} + RESULT_VARIABLE rv) + +if(NOT rv EQUAL 0) + message(STATUS \"extracting... [error clean up]\") + file(REMOVE_RECURSE \"\${ut_dir}\") + message(FATAL_ERROR \"error: extract of '\${filename}' failed\") +endif() + +# Analyze what came out of the tar file: +# +message(STATUS \"extracting... [analysis]\") +file(GLOB contents \"\${ut_dir}/*\") +list(LENGTH contents n) +if(NOT n EQUAL 1 OR NOT IS_DIRECTORY \"\${contents}\") + set(contents \"\${ut_dir}\") +endif() + +# Move \"the one\" directory to the final directory: +# +message(STATUS \"extracting... [rename]\") +file(REMOVE_RECURSE \${directory}) +get_filename_component(contents \${contents} ABSOLUTE) +file(RENAME \${contents} \${directory}) + +# Clean up: +# +message(STATUS \"extracting... [clean up]\") +file(REMOVE_RECURSE \"\${ut_dir}\") + +message(STATUS \"extracting... done\") +" +) + +endfunction(_ep_write_extractfile_script) + + +function(_ep_set_directories name) + get_property(prefix TARGET ${name} PROPERTY _EP_PREFIX) + if(NOT prefix) + get_property(prefix DIRECTORY PROPERTY EP_PREFIX) + if(NOT prefix) + get_property(base DIRECTORY PROPERTY EP_BASE) + if(NOT base) + set(prefix "${name}-prefix") + endif() + endif() + endif() + if(prefix) + set(tmp_default "${prefix}/tmp") + set(download_default "${prefix}/src") + set(source_default "${prefix}/src/${name}") + set(binary_default "${prefix}/src/${name}-build") + set(stamp_default "${prefix}/src/${name}-stamp") + set(install_default "${prefix}") + else() # assert(base) + set(tmp_default "${base}/tmp/${name}") + set(download_default "${base}/Download/${name}") + set(source_default "${base}/Source/${name}") + set(binary_default "${base}/Build/${name}") + set(stamp_default "${base}/Stamp/${name}") + set(install_default "${base}/Install/${name}") + endif() + get_property(build_in_source TARGET ${name} PROPERTY _EP_BUILD_IN_SOURCE) + if(build_in_source) + get_property(have_binary_dir TARGET ${name} PROPERTY _EP_BINARY_DIR SET) + if(have_binary_dir) + message(FATAL_ERROR + "External project ${name} has both BINARY_DIR and BUILD_IN_SOURCE!") + endif() + endif() + set(top "${CMAKE_CURRENT_BINARY_DIR}") + set(places stamp download source binary install tmp) + foreach(var ${places}) + string(TOUPPER "${var}" VAR) + get_property(${var}_dir TARGET ${name} PROPERTY _EP_${VAR}_DIR) + if(NOT ${var}_dir) + set(${var}_dir "${${var}_default}") + endif() + if(NOT IS_ABSOLUTE "${${var}_dir}") + get_filename_component(${var}_dir "${top}/${${var}_dir}" ABSOLUTE) + endif() + set_property(TARGET ${name} PROPERTY _EP_${VAR}_DIR "${${var}_dir}") + endforeach() + if(build_in_source) + get_property(source_dir TARGET ${name} PROPERTY _EP_SOURCE_DIR) + set_property(TARGET ${name} PROPERTY _EP_BINARY_DIR "${source_dir}") + endif() + + # Make the directories at CMake configure time *and* add a custom command + # to make them at build time. They need to exist at makefile generation + # time for Borland make and wmake so that CMake may generate makefiles + # with "cd C:\short\paths\with\no\spaces" commands in them. + # + # Additionally, the add_custom_command is still used in case somebody + # removes one of the necessary directories and tries to rebuild without + # re-running cmake. + foreach(var ${places}) + string(TOUPPER "${var}" VAR) + get_property(dir TARGET ${name} PROPERTY _EP_${VAR}_DIR) + file(MAKE_DIRECTORY "${dir}") + if(NOT EXISTS "${dir}") + message(FATAL_ERROR "dir '${dir}' does not exist after file(MAKE_DIRECTORY)") + endif() + endforeach() +endfunction(_ep_set_directories) + + +# IMPORTANT: this MUST be a macro and not a function because of the +# in-place replacements that occur in each ${var} +# +macro(_ep_replace_location_tags target_name) + set(vars ${ARGN}) + foreach(var ${vars}) + if(${var}) + foreach(dir SOURCE_DIR BINARY_DIR INSTALL_DIR TMP_DIR) + get_property(val TARGET ${target_name} PROPERTY _EP_${dir}) + string(REPLACE "<${dir}>" "${val}" ${var} "${${var}}") + endforeach() + endif() + endforeach() +endmacro() + + +function(_ep_write_initial_cache target_name script_filename args) + # Write out values into an initial cache, that will be passed to CMake with -C + set(script_initial_cache "") + set(regex "^([^:]+):([^=]+)=(.*)$") + set(setArg "") + foreach(line ${args}) + if("${line}" MATCHES "^-D") + if(setArg) + # This is required to build up lists in variables, or complete an entry + set(setArg "${setArg}${accumulator}\" CACHE ${type} \"Initial cache\" FORCE)") + set(script_initial_cache "${script_initial_cache}\n${setArg}") + set(accumulator "") + set(setArg "") + endif() + string(REGEX REPLACE "^-D" "" line ${line}) + if("${line}" MATCHES "${regex}") + string(REGEX MATCH "${regex}" match "${line}") + set(name "${CMAKE_MATCH_1}") + set(type "${CMAKE_MATCH_2}") + set(value "${CMAKE_MATCH_3}") + set(setArg "set(${name} \"${value}") + else() + message(WARNING "Line '${line}' does not match regex. Ignoring.") + endif() + else() + # Assume this is a list to append to the last var + set(accumulator "${accumulator};${line}") + endif() + endforeach() + # Catch the final line of the args + if(setArg) + set(setArg "${setArg}${accumulator}\" CACHE ${type} \"Initial cache\" FORCE)") + set(script_initial_cache "${script_initial_cache}\n${setArg}") + endif() + # Replace location tags. + _ep_replace_location_tags(${target_name} script_initial_cache) + # Write out the initial cache file to the location specified. + if(NOT EXISTS "${script_filename}.in") + file(WRITE "${script_filename}.in" "\@script_initial_cache\@\n") + endif() + configure_file("${script_filename}.in" "${script_filename}") +endfunction(_ep_write_initial_cache) + + +function(ExternalProjectWithFilename_Get_Property name) + foreach(var ${ARGN}) + string(TOUPPER "${var}" VAR) + get_property(${var} TARGET ${name} PROPERTY _EP_${VAR}) + if(NOT ${var}) + message(FATAL_ERROR "External project \"${name}\" has no ${var}") + endif() + set(${var} "${${var}}" PARENT_SCOPE) + endforeach() +endfunction(ExternalProjectWithFilename_Get_Property) + + +function(_ep_get_configure_command_id name cfg_cmd_id_var) + get_target_property(cmd ${name} _EP_CONFIGURE_COMMAND) + + if(cmd STREQUAL "") + # Explicit empty string means no configure step for this project + set(${cfg_cmd_id_var} "none" PARENT_SCOPE) + else() + if(NOT cmd) + # Default is "use cmake": + set(${cfg_cmd_id_var} "cmake" PARENT_SCOPE) + else() + # Otherwise we have to analyze the value: + if(cmd MATCHES "^[^;]*/configure") + set(${cfg_cmd_id_var} "configure" PARENT_SCOPE) + elseif(cmd MATCHES "^[^;]*/cmake" AND NOT cmd MATCHES ";-[PE];") + set(${cfg_cmd_id_var} "cmake" PARENT_SCOPE) + elseif(cmd MATCHES "config") + set(${cfg_cmd_id_var} "configure" PARENT_SCOPE) + else() + set(${cfg_cmd_id_var} "unknown:${cmd}" PARENT_SCOPE) + endif() + endif() + endif() +endfunction(_ep_get_configure_command_id) + + +function(_ep_get_build_command name step cmd_var) + set(cmd "${${cmd_var}}") + if(NOT cmd) + set(args) + _ep_get_configure_command_id(${name} cfg_cmd_id) + if(cfg_cmd_id STREQUAL "cmake") + # CMake project. Select build command based on generator. + get_target_property(cmake_generator ${name} _EP_CMAKE_GENERATOR) + if("${CMAKE_GENERATOR}" MATCHES "Make" AND + ("${cmake_generator}" MATCHES "Make" OR NOT cmake_generator)) + # The project uses the same Makefile generator. Use recursive make. + set(cmd "$(MAKE)") + if(step STREQUAL "INSTALL") + set(args install) + endif() + if(step STREQUAL "TEST") + set(args test) + endif() + else() + # Drive the project with "cmake --build". + get_target_property(cmake_command ${name} _EP_CMAKE_COMMAND) + if(cmake_command) + set(cmd "${cmake_command}") + else() + set(cmd "${CMAKE_COMMAND}") + endif() + set(args --build ${binary_dir} --config ${CMAKE_CFG_INTDIR}) + if(step STREQUAL "INSTALL") + list(APPEND args --target install) + endif() + # But for "TEST" drive the project with corresponding "ctest". + if(step STREQUAL "TEST") + string(REGEX REPLACE "^(.*/)cmake([^/]*)$" "\\1ctest\\2" cmd "${cmd}") + set(args "") + endif() + endif() + else() # if(cfg_cmd_id STREQUAL "configure") + # Non-CMake project. Guess "make" and "make install" and "make test". + # But use "$(MAKE)" to get recursive parallel make. + set(cmd "$(MAKE)") + if(step STREQUAL "INSTALL") + set(args install) + endif() + if(step STREQUAL "TEST") + set(args test) + endif() + endif() + + # Use user-specified arguments instead of default arguments, if any. + get_property(have_args TARGET ${name} PROPERTY _EP_${step}_ARGS SET) + if(have_args) + get_target_property(args ${name} _EP_${step}_ARGS) + endif() + + list(APPEND cmd ${args}) + endif() + + set(${cmd_var} "${cmd}" PARENT_SCOPE) +endfunction(_ep_get_build_command) + +function(_ep_write_log_script name step cmd_var) + ExternalProjectWithFilename_Get_Property(${name} stamp_dir) + set(command "${${cmd_var}}") + + set(make "") + set(code_cygpath_make "") + if("${command}" MATCHES "^\\$\\(MAKE\\)") + # GNU make recognizes the string "$(MAKE)" as recursive make, so + # ensure that it appears directly in the makefile. + string(REGEX REPLACE "^\\$\\(MAKE\\)" "\${make}" command "${command}") + set(make "-Dmake=$(MAKE)") + + if(WIN32 AND NOT CYGWIN) + set(code_cygpath_make " +if(\${make} MATCHES \"^/\") + execute_process( + COMMAND cygpath -w \${make} + OUTPUT_VARIABLE cygpath_make + ERROR_VARIABLE cygpath_make + RESULT_VARIABLE cygpath_error + OUTPUT_STRIP_TRAILING_WHITESPACE + ) + if(NOT cygpath_error) + set(make \${cygpath_make}) + endif() +endif() +") + endif() + endif() + + set(config "") + if("${CMAKE_CFG_INTDIR}" MATCHES "^\\$") + string(REPLACE "${CMAKE_CFG_INTDIR}" "\${config}" command "${command}") + set(config "-Dconfig=${CMAKE_CFG_INTDIR}") + endif() + + # Wrap multiple 'COMMAND' lines up into a second-level wrapper + # script so all output can be sent to one log file. + if("${command}" MATCHES ";COMMAND;") + set(code_execute_process " +${code_cygpath_make} +execute_process(COMMAND \${command} RESULT_VARIABLE result) +if(result) + set(msg \"Command failed (\${result}):\\n\") + foreach(arg IN LISTS command) + set(msg \"\${msg} '\${arg}'\") + endforeach(arg) + message(FATAL_ERROR \"\${msg}\") +endif() +") + set(code "") + set(cmd "") + set(sep "") + foreach(arg IN LISTS command) + if("x${arg}" STREQUAL "xCOMMAND") + set(code "${code}set(command \"${cmd}\")${code_execute_process}") + set(cmd "") + set(sep "") + else() + set(cmd "${cmd}${sep}${arg}") + set(sep ";") + endif() + endforeach() + set(code "set(ENV{VS_UNICODE_OUTPUT} \"\")\n${code}set(command \"${cmd}\")${code_execute_process}") + file(WRITE ${stamp_dir}/${name}-${step}-impl.cmake "${code}") + set(command ${CMAKE_COMMAND} "-Dmake=\${make}" "-Dconfig=\${config}" -P ${stamp_dir}/${name}-${step}-impl.cmake) + endif() + + # Wrap the command in a script to log output to files. + set(script ${stamp_dir}/${name}-${step}.cmake) + set(logbase ${stamp_dir}/${name}-${step}) + file(WRITE ${script} " +${code_cygpath_make} +set(ENV{VS_UNICODE_OUTPUT} \"\") +set(command \"${command}\") +execute_process( + COMMAND \${command} + RESULT_VARIABLE result + OUTPUT_FILE \"${logbase}-out.log\" + ERROR_FILE \"${logbase}-err.log\" + ) +if(result) + set(msg \"Command failed: \${result}\\n\") + foreach(arg IN LISTS command) + set(msg \"\${msg} '\${arg}'\") + endforeach(arg) + set(msg \"\${msg}\\nSee also\\n ${logbase}-*.log\\n\") + message(FATAL_ERROR \"\${msg}\") +else() + set(msg \"${name} ${step} command succeeded. See also ${logbase}-*.log\\n\") + message(STATUS \"\${msg}\") +endif() +") + set(command ${CMAKE_COMMAND} ${make} ${config} -P ${script}) + set(${cmd_var} "${command}" PARENT_SCOPE) +endfunction(_ep_write_log_script) + +# This module used to use "/${CMAKE_CFG_INTDIR}" directly and produced +# makefiles with "/./" in paths for custom command dependencies. Which +# resulted in problems with parallel make -j invocations. +# +# This function was added so that the suffix (search below for ${cfgdir}) is +# only set to "/${CMAKE_CFG_INTDIR}" when ${CMAKE_CFG_INTDIR} is not going to +# be "." (multi-configuration build systems like Visual Studio and Xcode...) +# +function(_ep_get_configuration_subdir_suffix suffix_var) + set(suffix "") + if(CMAKE_CONFIGURATION_TYPES) + set(suffix "/${CMAKE_CFG_INTDIR}") + endif() + set(${suffix_var} "${suffix}" PARENT_SCOPE) +endfunction(_ep_get_configuration_subdir_suffix) + + +function(ExternalProjectWithFilename_Add_StepTargets name) + set(steps ${ARGN}) + + _ep_get_configuration_subdir_suffix(cfgdir) + ExternalProjectWithFilename_Get_Property(${name} stamp_dir) + + foreach(step ${steps}) + add_custom_target(${name}-${step} + DEPENDS ${stamp_dir}${cfgdir}/${name}-${step}) + endforeach() +endfunction(ExternalProjectWithFilename_Add_StepTargets) + + +function(ExternalProjectWithFilename_Add_Step name step) + set(cmf_dir ${CMAKE_CURRENT_BINARY_DIR}/CMakeFiles) + ExternalProjectWithFilename_Get_Property(${name} stamp_dir) + + _ep_get_configuration_subdir_suffix(cfgdir) + + add_custom_command(APPEND + OUTPUT ${cmf_dir}${cfgdir}/${name}-complete + DEPENDS ${stamp_dir}${cfgdir}/${name}-${step} + ) + _ep_parse_arguments(ExternalProjectWithFilename_Add_Step + ${name} _EP_${step}_ "${ARGN}") + + # Steps depending on this step. + get_property(dependers TARGET ${name} PROPERTY _EP_${step}_DEPENDERS) + foreach(depender IN LISTS dependers) + add_custom_command(APPEND + OUTPUT ${stamp_dir}${cfgdir}/${name}-${depender} + DEPENDS ${stamp_dir}${cfgdir}/${name}-${step} + ) + endforeach() + + # Dependencies on files. + get_property(depends TARGET ${name} PROPERTY _EP_${step}_DEPENDS) + + # Dependencies on steps. + get_property(dependees TARGET ${name} PROPERTY _EP_${step}_DEPENDEES) + foreach(dependee IN LISTS dependees) + list(APPEND depends ${stamp_dir}${cfgdir}/${name}-${dependee}) + endforeach() + + # The command to run. + get_property(command TARGET ${name} PROPERTY _EP_${step}_COMMAND) + if(command) + set(comment "Performing ${step} step for '${name}'") + else() + set(comment "No ${step} step for '${name}'") + endif() + get_property(work_dir TARGET ${name} PROPERTY _EP_${step}_WORKING_DIRECTORY) + + # Replace list separators. + get_property(sep TARGET ${name} PROPERTY _EP_LIST_SEPARATOR) + if(sep AND command) + string(REPLACE "${sep}" "\\;" command "${command}") + endif() + + # Replace location tags. + _ep_replace_location_tags(${name} comment command work_dir) + + # Custom comment? + get_property(comment_set TARGET ${name} PROPERTY _EP_${step}_COMMENT SET) + if(comment_set) + get_property(comment TARGET ${name} PROPERTY _EP_${step}_COMMENT) + endif() + + # Run every time? + get_property(always TARGET ${name} PROPERTY _EP_${step}_ALWAYS) + if(always) + set_property(SOURCE ${stamp_dir}${cfgdir}/${name}-${step} PROPERTY SYMBOLIC 1) + set(touch) + else() + set(touch ${CMAKE_COMMAND} -E touch ${stamp_dir}${cfgdir}/${name}-${step}) + endif() + + # Wrap with log script? + get_property(log TARGET ${name} PROPERTY _EP_${step}_LOG) + if(command AND log) + _ep_write_log_script(${name} ${step} command) + endif() + + add_custom_command( + OUTPUT ${stamp_dir}${cfgdir}/${name}-${step} + COMMENT ${comment} + COMMAND ${command} + COMMAND ${touch} + DEPENDS ${depends} + WORKING_DIRECTORY ${work_dir} + VERBATIM + ) + + # Add custom "step target"? + get_property(step_targets TARGET ${name} PROPERTY _EP_STEP_TARGETS) + if(NOT step_targets) + get_property(step_targets DIRECTORY PROPERTY EP_STEP_TARGETS) + endif() + foreach(st ${step_targets}) + if("${st}" STREQUAL "${step}") + ExternalProjectWithFilename_Add_StepTargets(${name} ${step}) + break() + endif() + endforeach() +endfunction(ExternalProjectWithFilename_Add_Step) + + +function(_ep_add_mkdir_command name) + ExternalProjectWithFilename_Get_Property(${name} + source_dir binary_dir install_dir stamp_dir download_dir tmp_dir) + + _ep_get_configuration_subdir_suffix(cfgdir) + + ExternalProjectWithFilename_Add_Step(${name} mkdir + COMMENT "Creating directories for '${name}'" + COMMAND ${CMAKE_COMMAND} -E make_directory ${source_dir} + COMMAND ${CMAKE_COMMAND} -E make_directory ${binary_dir} + COMMAND ${CMAKE_COMMAND} -E make_directory ${install_dir} + COMMAND ${CMAKE_COMMAND} -E make_directory ${tmp_dir} + COMMAND ${CMAKE_COMMAND} -E make_directory ${stamp_dir}${cfgdir} + COMMAND ${CMAKE_COMMAND} -E make_directory ${download_dir} + ) +endfunction(_ep_add_mkdir_command) + + +function(_ep_get_git_version git_EXECUTABLE git_version_var) + if(git_EXECUTABLE) + execute_process( + COMMAND "${git_EXECUTABLE}" --version + OUTPUT_VARIABLE ov + OUTPUT_STRIP_TRAILING_WHITESPACE + ) + string(REGEX REPLACE "^git version (.+)$" "\\1" version "${ov}") + set(${git_version_var} "${version}" PARENT_SCOPE) + endif() +endfunction() + + +function(_ep_is_dir_empty dir empty_var) + file(GLOB gr "${dir}/*") + if("${gr}" STREQUAL "") + set(${empty_var} 1 PARENT_SCOPE) + else() + set(${empty_var} 0 PARENT_SCOPE) + endif() +endfunction() + + +function(_ep_add_download_command name) + ExternalProjectWithFilename_Get_Property(${name} source_dir stamp_dir download_dir tmp_dir) + + get_property(cmd_set TARGET ${name} PROPERTY _EP_DOWNLOAD_COMMAND SET) + get_property(cmd TARGET ${name} PROPERTY _EP_DOWNLOAD_COMMAND) + get_property(cvs_repository TARGET ${name} PROPERTY _EP_CVS_REPOSITORY) + get_property(svn_repository TARGET ${name} PROPERTY _EP_SVN_REPOSITORY) + get_property(git_repository TARGET ${name} PROPERTY _EP_GIT_REPOSITORY) + get_property(url TARGET ${name} PROPERTY _EP_URL) + get_property(fname TARGET ${name} PROPERTY _EP_FILENAME) + + # TODO: Perhaps file:// should be copied to download dir before extraction. + string(REGEX REPLACE "^file://" "" url "${url}") + + set(depends) + set(comment) + set(work_dir) + + if(cmd_set) + set(work_dir ${download_dir}) + elseif(cvs_repository) + find_package(CVS) + if(NOT CVS_EXECUTABLE) + message(FATAL_ERROR "error: could not find cvs for checkout of ${name}") + endif() + + get_target_property(cvs_module ${name} _EP_CVS_MODULE) + if(NOT cvs_module) + message(FATAL_ERROR "error: no CVS_MODULE") + endif() + + get_property(cvs_tag TARGET ${name} PROPERTY _EP_CVS_TAG) + + set(repository ${cvs_repository}) + set(module ${cvs_module}) + set(tag ${cvs_tag}) + configure_file( + "${CMAKE_ROOT}/Modules/RepositoryInfo.txt.in" + "${stamp_dir}/${name}-cvsinfo.txt" + @ONLY + ) + + get_filename_component(src_name "${source_dir}" NAME) + get_filename_component(work_dir "${source_dir}" PATH) + set(comment "Performing download step (CVS checkout) for '${name}'") + set(cmd ${CVS_EXECUTABLE} -d ${cvs_repository} -q co ${cvs_tag} -d ${src_name} ${cvs_module}) + list(APPEND depends ${stamp_dir}/${name}-cvsinfo.txt) + elseif(svn_repository) + find_package(Subversion) + if(NOT Subversion_SVN_EXECUTABLE) + message(FATAL_ERROR "error: could not find svn for checkout of ${name}") + endif() + + get_property(svn_revision TARGET ${name} PROPERTY _EP_SVN_REVISION) + get_property(svn_username TARGET ${name} PROPERTY _EP_SVN_USERNAME) + get_property(svn_password TARGET ${name} PROPERTY _EP_SVN_PASSWORD) + get_property(svn_trust_cert TARGET ${name} PROPERTY _EP_SVN_TRUST_CERT) + + set(repository "${svn_repository} user=${svn_username} password=${svn_password}") + set(module) + set(tag ${svn_revision}) + configure_file( + "${CMAKE_ROOT}/Modules/RepositoryInfo.txt.in" + "${stamp_dir}/${name}-svninfo.txt" + @ONLY + ) + + get_filename_component(src_name "${source_dir}" NAME) + get_filename_component(work_dir "${source_dir}" PATH) + set(comment "Performing download step (SVN checkout) for '${name}'") + set(svn_user_pw_args "") + if(svn_username) + set(svn_user_pw_args ${svn_user_pw_args} "--username=${svn_username}") + endif() + if(svn_password) + set(svn_user_pw_args ${svn_user_pw_args} "--password=${svn_password}") + endif() + if(svn_trust_cert) + set(svn_trust_cert_args --trust-server-cert) + endif() + set(cmd ${Subversion_SVN_EXECUTABLE} co ${svn_repository} ${svn_revision} + --non-interactive ${svn_trust_cert_args} ${svn_user_pw_args} ${src_name}) + list(APPEND depends ${stamp_dir}/${name}-svninfo.txt) + elseif(git_repository) + find_package(Git) + if(NOT GIT_EXECUTABLE) + message(FATAL_ERROR "error: could not find git for clone of ${name}") + endif() + + # The git submodule update '--recursive' flag requires git >= v1.6.5 + # + _ep_get_git_version("${GIT_EXECUTABLE}" git_version) + if(git_version VERSION_LESS 1.6.5) + message(FATAL_ERROR "error: git version 1.6.5 or later required for 'git submodule update --recursive': git_version='${git_version}'") + endif() + + get_property(git_tag TARGET ${name} PROPERTY _EP_GIT_TAG) + if(NOT git_tag) + set(git_tag "master") + endif() + + set(repository ${git_repository}) + set(module) + set(tag ${git_tag}) + configure_file( + "${CMAKE_ROOT}/Modules/RepositoryInfo.txt.in" + "${stamp_dir}/${name}-gitinfo.txt" + @ONLY + ) + + get_filename_component(src_name "${source_dir}" NAME) + get_filename_component(work_dir "${source_dir}" PATH) + + # Since git clone doesn't succeed if the non-empty source_dir exists, + # create a cmake script to invoke as download command. + # The script will delete the source directory and then call git clone. + # + _ep_write_gitclone_script(${tmp_dir}/${name}-gitclone.cmake ${source_dir} + ${GIT_EXECUTABLE} ${git_repository} ${git_tag} ${src_name} ${work_dir} + ) + set(comment "Performing download step (git clone) for '${name}'") + set(cmd ${CMAKE_COMMAND} -P ${tmp_dir}/${name}-gitclone.cmake) + list(APPEND depends ${stamp_dir}/${name}-gitinfo.txt) + elseif(url) + get_filename_component(work_dir "${source_dir}" PATH) + get_property(md5 TARGET ${name} PROPERTY _EP_URL_MD5) + set(repository "external project URL") + set(module "${url}") + set(tag "${md5}") + configure_file( + "${CMAKE_ROOT}/Modules/RepositoryInfo.txt.in" + "${stamp_dir}/${name}-urlinfo.txt" + @ONLY + ) + list(APPEND depends ${stamp_dir}/${name}-urlinfo.txt) + if(IS_DIRECTORY "${url}") + get_filename_component(abs_dir "${url}" ABSOLUTE) + set(comment "Performing download step (DIR copy) for '${name}'") + set(cmd ${CMAKE_COMMAND} -E remove_directory ${source_dir} + COMMAND ${CMAKE_COMMAND} -E copy_directory ${abs_dir} ${source_dir}) + else() + if("${url}" MATCHES "^[a-z]+://") + # TODO: Should download and extraction be different steps? + + # MODIFICATION HERE: allows setting filename for urls + # where filename is not embedded, such as github + if ("${fname}" STREQUAL "") + string(REGEX MATCH "[^/\\?]*$" fname "${url}") + endif() + # this is set by filename now + if(NOT "${fname}" MATCHES "(\\.|=)(bz2|tar|tgz|tar\\.gz|zip)$") + string(REGEX MATCH "([^/\\?]+(\\.|=)(bz2|tar|tgz|tar\\.gz|zip))/.*$" match_result "${url}") + set(fname "${CMAKE_MATCH_1}") + endif() + if(NOT "${fname}" MATCHES "(\\.|=)(bz2|tar|tgz|tar\\.gz|zip)$") + message(FATAL_ERROR "Could not extract tarball filename from url:\n ${url}") + endif() + string(REPLACE ";" "-" fname "${fname}") + set(file ${download_dir}/${fname}) + get_property(timeout TARGET ${name} PROPERTY _EP_TIMEOUT) + _ep_write_downloadfile_script("${stamp_dir}/download-${name}.cmake" "${url}" "${file}" "${timeout}" "${md5}") + set(cmd ${CMAKE_COMMAND} -P ${stamp_dir}/download-${name}.cmake + COMMAND) + set(comment "Performing download step (download, verify and extract) for '${name}'") + else() + set(file "${url}") + set(comment "Performing download step (verify and extract) for '${name}'") + endif() + _ep_write_verifyfile_script("${stamp_dir}/verify-${name}.cmake" "${file}" "${md5}") + list(APPEND cmd ${CMAKE_COMMAND} -P ${stamp_dir}/verify-${name}.cmake) + _ep_write_extractfile_script("${stamp_dir}/extract-${name}.cmake" "${name}" "${file}" "${source_dir}") + list(APPEND cmd ${CMAKE_COMMAND} -P ${stamp_dir}/extract-${name}.cmake) + endif() + else() + _ep_is_dir_empty("${source_dir}" empty) + if(${empty}) + message(SEND_ERROR "error: no download info for '${name}' -- please specify existing/non-empty SOURCE_DIR or one of URL, CVS_REPOSITORY and CVS_MODULE, SVN_REPOSITORY, GIT_REPOSITORY or DOWNLOAD_COMMAND") + endif() + endif() + + get_property(log TARGET ${name} PROPERTY _EP_LOG_DOWNLOAD) + if(log) + set(log LOG 1) + else() + set(log "") + endif() + + ExternalProjectWithFilename_Add_Step(${name} download + COMMENT ${comment} + COMMAND ${cmd} + WORKING_DIRECTORY ${work_dir} + DEPENDS ${depends} + DEPENDEES mkdir + ${log} + ) +endfunction(_ep_add_download_command) + + +function(_ep_add_update_command name) + ExternalProjectWithFilename_Get_Property(${name} source_dir) + + get_property(cmd_set TARGET ${name} PROPERTY _EP_UPDATE_COMMAND SET) + get_property(cmd TARGET ${name} PROPERTY _EP_UPDATE_COMMAND) + get_property(cvs_repository TARGET ${name} PROPERTY _EP_CVS_REPOSITORY) + get_property(svn_repository TARGET ${name} PROPERTY _EP_SVN_REPOSITORY) + get_property(git_repository TARGET ${name} PROPERTY _EP_GIT_REPOSITORY) + + set(work_dir) + set(comment) + set(always) + + if(cmd_set) + set(work_dir ${source_dir}) + elseif(cvs_repository) + if(NOT CVS_EXECUTABLE) + message(FATAL_ERROR "error: could not find cvs for update of ${name}") + endif() + set(work_dir ${source_dir}) + set(comment "Performing update step (CVS update) for '${name}'") + get_property(cvs_tag TARGET ${name} PROPERTY _EP_CVS_TAG) + set(cmd ${CVS_EXECUTABLE} -d ${cvs_repository} -q up -dP ${cvs_tag}) + set(always 1) + elseif(svn_repository) + if(NOT Subversion_SVN_EXECUTABLE) + message(FATAL_ERROR "error: could not find svn for update of ${name}") + endif() + set(work_dir ${source_dir}) + set(comment "Performing update step (SVN update) for '${name}'") + get_property(svn_revision TARGET ${name} PROPERTY _EP_SVN_REVISION) + get_property(svn_username TARGET ${name} PROPERTY _EP_SVN_USERNAME) + get_property(svn_password TARGET ${name} PROPERTY _EP_SVN_PASSWORD) + get_property(svn_trust_cert TARGET ${name} PROPERTY _EP_SVN_TRUST_CERT) + set(svn_user_pw_args "") + if(svn_username) + set(svn_user_pw_args ${svn_user_pw_args} "--username=${svn_username}") + endif() + if(svn_password) + set(svn_user_pw_args ${svn_user_pw_args} "--password=${svn_password}") + endif() + if(svn_trust_cert) + set(svn_trust_cert_args --trust-server-cert) + endif() + set(cmd ${Subversion_SVN_EXECUTABLE} up ${svn_revision} + --non-interactive ${svn_trust_cert_args} ${svn_user_pw_args}) + set(always 1) + elseif(git_repository) + if(NOT GIT_EXECUTABLE) + message(FATAL_ERROR "error: could not find git for fetch of ${name}") + endif() + set(work_dir ${source_dir}) + set(comment "Performing update step (git fetch) for '${name}'") + get_property(git_tag TARGET ${name} PROPERTY _EP_GIT_TAG) + if(NOT git_tag) + set(git_tag "master") + endif() + set(cmd ${GIT_EXECUTABLE} fetch + COMMAND ${GIT_EXECUTABLE} checkout ${git_tag} + COMMAND ${GIT_EXECUTABLE} submodule update --recursive + ) + set(always 1) + endif() + + get_property(log TARGET ${name} PROPERTY _EP_LOG_UPDATE) + if(log) + set(log LOG 1) + else() + set(log "") + endif() + + ExternalProjectWithFilename_Add_Step(${name} update + COMMENT ${comment} + COMMAND ${cmd} + ALWAYS ${always} + WORKING_DIRECTORY ${work_dir} + DEPENDEES download + ${log} + ) +endfunction(_ep_add_update_command) + + +function(_ep_add_patch_command name) + ExternalProjectWithFilename_Get_Property(${name} source_dir) + + get_property(cmd_set TARGET ${name} PROPERTY _EP_PATCH_COMMAND SET) + get_property(cmd TARGET ${name} PROPERTY _EP_PATCH_COMMAND) + + set(work_dir) + + if(cmd_set) + set(work_dir ${source_dir}) + endif() + + ExternalProjectWithFilename_Add_Step(${name} patch + COMMAND ${cmd} + WORKING_DIRECTORY ${work_dir} + DEPENDEES download + ) +endfunction(_ep_add_patch_command) + + +# TODO: Make sure external projects use the proper compiler +function(_ep_add_configure_command name) + ExternalProjectWithFilename_Get_Property(${name} source_dir binary_dir tmp_dir) + + _ep_get_configuration_subdir_suffix(cfgdir) + + # Depend on other external projects (file-level). + set(file_deps) + get_property(deps TARGET ${name} PROPERTY _EP_DEPENDS) + foreach(dep IN LISTS deps) + get_property(dep_stamp_dir TARGET ${dep} PROPERTY _EP_STAMP_DIR) + list(APPEND file_deps ${dep_stamp_dir}${cfgdir}/${dep}-done) + endforeach() + + get_property(cmd_set TARGET ${name} PROPERTY _EP_CONFIGURE_COMMAND SET) + if(cmd_set) + get_property(cmd TARGET ${name} PROPERTY _EP_CONFIGURE_COMMAND) + else() + get_target_property(cmake_command ${name} _EP_CMAKE_COMMAND) + if(cmake_command) + set(cmd "${cmake_command}") + else() + set(cmd "${CMAKE_COMMAND}") + endif() + + get_property(cmake_args TARGET ${name} PROPERTY _EP_CMAKE_ARGS) + list(APPEND cmd ${cmake_args}) + + # If there are any CMAKE_CACHE_ARGS, write an initial cache and use it + get_property(cmake_cache_args TARGET ${name} PROPERTY _EP_CMAKE_CACHE_ARGS) + if(cmake_cache_args) + set(_ep_cache_args_script "${tmp_dir}/${name}-cache.cmake") + _ep_write_initial_cache(${name} "${_ep_cache_args_script}" "${cmake_cache_args}") + list(APPEND cmd "-C${_ep_cache_args_script}") + endif() + + get_target_property(cmake_generator ${name} _EP_CMAKE_GENERATOR) + if(cmake_generator) + list(APPEND cmd "-G${cmake_generator}" "${source_dir}") + else() + if(CMAKE_EXTRA_GENERATOR) + list(APPEND cmd "-G${CMAKE_EXTRA_GENERATOR} - ${CMAKE_GENERATOR}" + "${source_dir}") + else() + list(APPEND cmd "-G${CMAKE_GENERATOR}" "${source_dir}") + endif() + endif() + endif() + + # If anything about the configure command changes, (command itself, cmake + # used, cmake args or cmake generator) then re-run the configure step. + # Fixes issue http://public.kitware.com/Bug/view.php?id=10258 + # + if(NOT EXISTS ${tmp_dir}/${name}-cfgcmd.txt.in) + file(WRITE ${tmp_dir}/${name}-cfgcmd.txt.in "cmd='\@cmd\@'\n") + endif() + configure_file(${tmp_dir}/${name}-cfgcmd.txt.in ${tmp_dir}/${name}-cfgcmd.txt) + list(APPEND file_deps ${tmp_dir}/${name}-cfgcmd.txt) + list(APPEND file_deps ${_ep_cache_args_script}) + + get_property(log TARGET ${name} PROPERTY _EP_LOG_CONFIGURE) + if(log) + set(log LOG 1) + else() + set(log "") + endif() + + ExternalProjectWithFilename_Add_Step(${name} configure + COMMAND ${cmd} + WORKING_DIRECTORY ${binary_dir} + DEPENDEES update patch + DEPENDS ${file_deps} + ${log} + ) +endfunction(_ep_add_configure_command) + + +function(_ep_add_build_command name) + ExternalProjectWithFilename_Get_Property(${name} binary_dir) + + get_property(cmd_set TARGET ${name} PROPERTY _EP_BUILD_COMMAND SET) + if(cmd_set) + get_property(cmd TARGET ${name} PROPERTY _EP_BUILD_COMMAND) + else() + _ep_get_build_command(${name} BUILD cmd) + endif() + + get_property(log TARGET ${name} PROPERTY _EP_LOG_BUILD) + if(log) + set(log LOG 1) + else() + set(log "") + endif() + + ExternalProjectWithFilename_Add_Step(${name} build + COMMAND ${cmd} + WORKING_DIRECTORY ${binary_dir} + DEPENDEES configure + ${log} + ) +endfunction(_ep_add_build_command) + + +function(_ep_add_install_command name) + ExternalProjectWithFilename_Get_Property(${name} binary_dir) + + get_property(cmd_set TARGET ${name} PROPERTY _EP_INSTALL_COMMAND SET) + if(cmd_set) + get_property(cmd TARGET ${name} PROPERTY _EP_INSTALL_COMMAND) + else() + _ep_get_build_command(${name} INSTALL cmd) + endif() + + get_property(log TARGET ${name} PROPERTY _EP_LOG_INSTALL) + if(log) + set(log LOG 1) + else() + set(log "") + endif() + + ExternalProjectWithFilename_Add_Step(${name} install + COMMAND ${cmd} + WORKING_DIRECTORY ${binary_dir} + DEPENDEES build + ${log} + ) +endfunction(_ep_add_install_command) + + +function(_ep_add_test_command name) + ExternalProjectWithFilename_Get_Property(${name} binary_dir) + + get_property(before TARGET ${name} PROPERTY _EP_TEST_BEFORE_INSTALL) + get_property(after TARGET ${name} PROPERTY _EP_TEST_AFTER_INSTALL) + get_property(cmd_set TARGET ${name} PROPERTY _EP_TEST_COMMAND SET) + + # Only actually add the test step if one of the test related properties is + # explicitly set. (i.e. the test step is omitted unless requested...) + # + if(cmd_set OR before OR after) + if(cmd_set) + get_property(cmd TARGET ${name} PROPERTY _EP_TEST_COMMAND) + else() + _ep_get_build_command(${name} TEST cmd) + endif() + + if(before) + set(dep_args DEPENDEES build DEPENDERS install) + else() + set(dep_args DEPENDEES install) + endif() + + get_property(log TARGET ${name} PROPERTY _EP_LOG_TEST) + if(log) + set(log LOG 1) + else() + set(log "") + endif() + + ExternalProjectWithFilename_Add_Step(${name} test + COMMAND ${cmd} + WORKING_DIRECTORY ${binary_dir} + ${dep_args} + ${log} + ) + endif() +endfunction(_ep_add_test_command) + + +function(ExternalProjectWithFilename_Add name) + _ep_get_configuration_subdir_suffix(cfgdir) + + # Add a custom target for the external project. + set(cmf_dir ${CMAKE_CURRENT_BINARY_DIR}/CMakeFiles) + add_custom_target(${name} ALL DEPENDS ${cmf_dir}${cfgdir}/${name}-complete) + set_property(TARGET ${name} PROPERTY _EP_IS_EXTERNAL_PROJECT 1) + _ep_parse_arguments(ExternalProjectWithFilename_Add ${name} _EP_ "${ARGN}") + _ep_set_directories(${name}) + ExternalProjectWithFilename_Get_Property(${name} stamp_dir) + + # The 'complete' step depends on all other steps and creates a + # 'done' mark. A dependent external project's 'configure' step + # depends on the 'done' mark so that it rebuilds when this project + # rebuilds. It is important that 'done' is not the output of any + # custom command so that CMake does not propagate build rules to + # other external project targets. + add_custom_command( + OUTPUT ${cmf_dir}${cfgdir}/${name}-complete + COMMENT "Completed '${name}'" + COMMAND ${CMAKE_COMMAND} -E make_directory ${cmf_dir}${cfgdir} + COMMAND ${CMAKE_COMMAND} -E touch ${cmf_dir}${cfgdir}/${name}-complete + COMMAND ${CMAKE_COMMAND} -E touch ${stamp_dir}${cfgdir}/${name}-done + DEPENDS ${stamp_dir}${cfgdir}/${name}-install + VERBATIM + ) + + + # Depend on other external projects (target-level). + get_property(deps TARGET ${name} PROPERTY _EP_DEPENDS) + foreach(arg IN LISTS deps) + add_dependencies(${name} ${arg}) + endforeach() + + # Set up custom build steps based on the target properties. + # Each step depends on the previous one. + # + # The target depends on the output of the final step. + # (Already set up above in the DEPENDS of the add_custom_target command.) + # + _ep_add_mkdir_command(${name}) + _ep_add_download_command(${name}) + _ep_add_update_command(${name}) + _ep_add_patch_command(${name}) + _ep_add_configure_command(${name}) + _ep_add_build_command(${name}) + _ep_add_install_command(${name}) + + # Test is special in that it might depend on build, or it might depend + # on install. + # + _ep_add_test_command(${name}) +endfunction(ExternalProjectWithFilename_Add) diff --git a/cmake/arkcmake/MacroCheckCCompilerFlagSSP.cmake b/cmake/arkcmake/MacroCheckCCompilerFlagSSP.cmake new file mode 100644 index 0000000..b64fb45 --- /dev/null +++ b/cmake/arkcmake/MacroCheckCCompilerFlagSSP.cmake @@ -0,0 +1,26 @@ +# - 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, +# +# 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) + diff --git a/cmake/arkcmake/MacroEnsureOutOfSourceBuild.cmake b/cmake/arkcmake/MacroEnsureOutOfSourceBuild.cmake new file mode 100644 index 0000000..3ff891b --- /dev/null +++ b/cmake/arkcmake/MacroEnsureOutOfSourceBuild.cmake @@ -0,0 +1,19 @@ +# - MACRO_ENSURE_OUT_OF_SOURCE_BUILD() +# MACRO_ENSURE_OUT_OF_SOURCE_BUILD() + +# Copyright (c) 2006, Alexander Neundorf, +# +# 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 diff --git a/cmake/arkcmake/updateArkcmake.py b/cmake/arkcmake/updateArkcmake.py new file mode 100755 index 0000000..246b69d --- /dev/null +++ b/cmake/arkcmake/updateArkcmake.py @@ -0,0 +1,19 @@ +#!/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"]) diff --git a/cmake/mavlink.bmp b/cmake/mavlink.bmp new file mode 100644 index 0000000..57b0116 Binary files /dev/null and b/cmake/mavlink.bmp differ diff --git a/cmake/mavlink.png b/cmake/mavlink.png new file mode 100644 index 0000000..1f665fe Binary files /dev/null and b/cmake/mavlink.png differ diff --git a/config.cmake.in b/config.cmake.in new file mode 100644 index 0000000..fd19d4f --- /dev/null +++ b/config.cmake.in @@ -0,0 +1,27 @@ +if (@PKG_NAME@_CONFIG_INCLUDED) + return() +endif() +set(@PKG_NAME@_CONFIG_INCLUDED TRUE) + +set(@PKG_NAME@_INCLUDE_DIRS "@CMAKE_INSTALL_PREFIX@/include") +set(@PKG_NAME@_DIALECTS @PKG_MAVLINK_DIALECTS@) + +foreach(lib @PKG_LIBRARIES@) + set(onelib "${lib}-NOTFOUND") + find_library(onelib ${lib} + PATHS "@CMAKE_INSTALL_PREFIX@/@CMAKE_INSTALL_LIBDIR@" + NO_DEFAULT_PATH + ) + if(NOT onelib) + message(FATAL_ERROR "Library '${lib}' in package @PKG_NAME@ is not installed properly") + endif() + list(APPEND @PKG_NAME@_LIBRARIES ${onelib}) +endforeach() + +foreach(dep @PKG_DEPENDS@) + if(NOT ${dep}_FOUND) + find_package(${dep}) + endif() + list(APPEND @PKG_NAME@_INCLUDE_DIRS ${${dep}_INCLUDE_DIRS}) + list(APPEND @PKG_NAME@_LIBRARIES ${${dep}_LIBRARIES}) +endforeach() diff --git a/config.h.in b/config.h.in new file mode 100644 index 0000000..6b10f6c --- /dev/null +++ b/config.h.in @@ -0,0 +1 @@ +#define MAVLINK_VERSION "${PROJECT_VERSION}" diff --git a/doc/Doxyfile b/doc/Doxyfile new file mode 100755 index 0000000..4ab7c0e --- /dev/null +++ b/doc/Doxyfile @@ -0,0 +1,1521 @@ +# Doxyfile 1.6.1 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded +# by quotes) that should identify the project. + +PROJECT_NAME = "PIXHAWK IMU / Autopilot" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, +# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrilic, Slovak, +# Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = YES + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = YES + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = NO + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful is your file systems +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 8 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = YES + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it parses. +# With this tag you can assign which parser to use for a given extension. +# Doxygen has a built-in mapping, but you can override or extend it using this tag. +# The format is ext=language, where ext is a file extension, and language is one of +# the parsers supported by doxygen: IDL, Java, Javascript, C#, C, C++, D, PHP, +# Objective-C, Python, Fortran, VHDL, C, C++. For instance to make doxygen treat +# .inc files as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. Note that for custom extensions you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. + +EXTENSION_MAPPING = + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate getter +# and setter methods for a property. Setting this option to YES (the default) +# will make doxygen to replace the get and set methods by a property in the +# documentation. This will only work if the methods are indeed getting or +# setting a simple type. If this is not the case, or you want to show the +# methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = NO + +# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to +# determine which symbols to keep in memory and which to flush to disk. +# When the cache is full, less often used symbols will be written to disk. +# For small to medium size projects (<1000 input files) the default value is +# probably good enough. For larger projects a too small cache size can cause +# doxygen to be busy swapping symbols to and from disk most of the time +# causing a significant performance penality. +# If the system has enough physical memory increasing the cache will improve the +# performance by keeping more symbols in memory. Note that the value works on +# a logarithmic scale so increasing the size by one will rougly double the +# memory usage. The cache size is given by this formula: +# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, +# corresponding to a cache size of 2^16 = 65536 symbols + +SYMBOL_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = YES + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = YES + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespace are hidden. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the (brief and detailed) documentation of class members so that constructors and destructors are listed first. If set to NO (the default) the constructors will appear in the respective orders defined by SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or define consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and defines in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# If the sources in your project are distributed over multiple directories +# then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy +# in the documentation. The default is NO. + +SHOW_DIRECTORIES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. +# This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed by +# doxygen. The layout file controls the global structure of the generated output files +# in an output format independent way. The create the layout file that represents +# doxygen's defaults, run doxygen with the -l option. You can optionally specify a +# file name after the option, if omitted DoxygenLayout.xml will be used as the name +# of the layout file. + +LAYOUT_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = YES + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be abled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = YES + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = doxy.log + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = .. + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx +# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py *.f90 + +FILE_PATTERNS = *.c *.h *.hpp *.hxx *.cc *.cpp *.cxx *.dox +#FILE_PATTERNS = + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. + +EXCLUDE = ../Debug \ + ../Release \ + ../external \ + ../testing \ + ../tools \ + ../arm7/include \ + ../measurements + +# The EXCLUDE_SYMLINKS tag can be used select whether or not files or +# directories that are symbolic links (a Unix filesystem feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. +# If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. +# Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. +# The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER +# is applied to all files. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = YES + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C and C++ comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = YES + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. +# Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = NO + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If the tag is left blank doxygen +# will generate a default style sheet. Note that doxygen will try to copy +# the style sheet file to the HTML output directory, so don't put your own +# stylesheet in the HTML output directory as well, or it will be erased! + +HTML_STYLESHEET = + +# If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, +# files or namespaces will be aligned in HTML using tables. If set to +# NO a bullet list will be used. + +HTML_ALIGN_MEMBERS = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. For this to work a browser that supports +# JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox +# Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari). + +HTML_DYNAMIC_SECTIONS = NO + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and QHP_VIRTUAL_FOLDER +# are set, an additional index file will be generated that can be used as input for +# Qt's qhelpgenerator to generate a Qt Compressed Help (.qch) of the generated +# HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to add. +# For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the custom filter to add.For more information please see +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this project's +# filter section matches. +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index at +# top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. + +DISABLE_INDEX = NO + +# This tag can be used to set the number of enum values (range [1..20]) +# that doxygen will group on one line in the generated HTML documentation. + +ENUM_VALUES_PER_LINE = 4 + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. + +GENERATE_TREEVIEW = NO + +# By enabling USE_INLINE_TREES, doxygen will generate the Groups, Directories, +# and Class Hierarchy pages using a tree view instead of an ordered list. + +USE_INLINE_TREES = NO + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# When the SEARCHENGINE tag is enable doxygen will generate a search box for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using HTML help (GENERATE_HTMLHELP) or Qt help (GENERATE_QHP) +# there is already a search function so this one should typically +# be disabled. + +SEARCHENGINE = YES + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, a4wide, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = a4wide + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include source code with syntax highlighting in the LaTeX output. Note that which sources are shown also depends on other settings such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. +# This is useful +# if you want to understand what is going on. +# On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# in the INCLUDE_PATH (see below) will be search if a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = IMU_PIXHAWK_V200 IMU_PIXHAWK_V210 + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all function-like macros that are alone +# on a line, have an all uppercase name, and do not end with a semicolon. Such +# function macros are typically used for boiler-plate code, and will confuse +# the parser if not removed. + +SKIP_FUNCTION_MACROS = NO + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. +# Optionally an initial location of the external documentation +# can be added for each tagfile. The format of a tag file without +# this location is as follows: +# +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths or +# URLs. If a location is present for each tag, the installdox tool +# does not have to be run to correct the links. +# Note that each tag file must have a unique name +# (where the name does NOT include the path) +# If a tag file is not located in the directory in which doxygen +# is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option is superseded by the HAVE_DOT option below. This is only a +# fallback. It is recommended to install and use dot, since it yields more +# powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = YES + +# By default doxygen will write a font called FreeSans.ttf to the output +# directory and reference it in all dot files that doxygen generates. This +# font does not include all possible unicode characters however, so when you need +# these (or just want a differently looking font) you can specify the font name +# using DOT_FONTNAME. You need need to make sure dot is able to find the font, +# which can be done by putting it in a standard location or by setting the +# DOTFONTPATH environment variable or by setting DOT_FONTPATH to the directory +# containing the font. + +DOT_FONTNAME = FreeSans + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the output directory to look for the +# FreeSans.ttf font (which doxygen will put there itself). If you specify a +# different font using DOT_FONTNAME you can set the path where dot +# can find it using this tag. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# the CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are png, jpg, or gif +# If left blank png will be used. + +DOT_IMAGE_FORMAT = png + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = YES + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/doc/README b/doc/README new file mode 100644 index 0000000..eefcb03 --- /dev/null +++ b/doc/README @@ -0,0 +1,9 @@ +MAVLink Micro Air Vehicle Message Marshalling Library + +The mavlink_to_html_table.xsl file is used to transform the MAVLink XML into a human-readable HTML table for online documentation. + +For more information, please visit: + +http://qgroundcontrol.org/mavlink/start + +(c) 2009-2010 Lorenz Meier / PIXHAWK Team diff --git a/doc/mavlink.css b/doc/mavlink.css new file mode 100644 index 0000000..9c0acb3 --- /dev/null +++ b/doc/mavlink.css @@ -0,0 +1,80 @@ +body { + font-family:'Helvetica',Arial; + font-size:90%; + margin: 80px; +} + +h1 { + margin-top: 2em; +} + +h2 { + margin-top: 1em; +} + +h3 { + margin-top: 0.8em; + font-size:150%; +} + +p.description { + font-style:italic; +} + +table { + margin-bottom: 5em; +} + +table.sortable { + border: 1px solid #656575; + width: 100%; +} + +table.sortable th { + margin: 5px; +} + +#tr:nth-child(odd) { background-color:#eee; } +#tr:nth-child(even) { background-color:#fff; } + +table.sortable thead { + background-color:#eee; + color:#666666; + font-weight: bold; + cursor: default; +} + +table.sortable td { + margin: 5px 5px 20px 5px; + vertical-align: top; +} + +table.sortable td.mavlink_name { + color:#226633; + font-weight: bold; + width: 25%; + vertical-align: top; +} + +table.sortable td.mavlink_mission_param { + color:#334455; + font-weight: bold; + width: 25%; +} + +table.sortable td.mavlink_type { + color:#323232; + font-weight: normal; + width: 12%; +} + +table.sortable td.mavlink_comment { + color:#555555; + font-weight: normal; + width: 60%; +} + +p.description { + color:#808080; + font-weight: normal; +} \ No newline at end of file diff --git a/doc/mavlink.php b/doc/mavlink.php new file mode 100644 index 0000000..40e37bf --- /dev/null +++ b/doc/mavlink.php @@ -0,0 +1,79 @@ +loadXML($xml); + +// Load stylesheet XSL file +$xsl = file_get_contents($xsl_file_name); +$xsl_doc = new DomDocument; +$xsl_doc->loadXML($xsl); + +$xsltproc = new XsltProcessor(); +$xsltproc->importStylesheet($xsl_doc); +?> + + + + + MAVLINK Common Message set specifications + + + +

MAVLINK Common Message Set

+ +

+These messages define the common message set, which is the reference message set implemented by most ground control stations and autopilots. +

+ +transformToXML($xml_doc)) +{ + echo $html; +} +else +{ + trigger_error("XSL transformation failed",E_USER_ERROR); +} + +?> + +
+
+ +

+Messages are defined by the common.xml file. The C packing/unpacking code is generated from this specification, as well as the HTML documentaiton in the section above.
+
+The XML displayed here is updated on every commit and therefore up-to-date. +

+ + +parse_code(); +// +//echo $display_xml; + +?> \ No newline at end of file diff --git a/doc/mavlink_to_html_table.xsl b/doc/mavlink_to_html_table.xsl new file mode 100644 index 0000000..4f0981b --- /dev/null +++ b/doc/mavlink_to_html_table.xsl @@ -0,0 +1,109 @@ + + + + + +

MAVLink Include Files

+

Including files:

+
+ + +

MAVLink Type Enumerations

+ +
+ + +

MAVLink Messages

+ +
+ + + + + + + + +

+ + + + + + + + + + + +
Field NameTypeDescription
+
+ + + + + + + + + + +

MAVLink Protocol Version

+

This file has protocol version: . The version numbers range from 1-255.

+
+ + + + + ENUM_ + + + + +

+ + + + + + + + + + + +
CMD IDField NameDescription
+
+ + + + + + + + + + + + +
+ +
+ + + + + Mission Param # + + + + + +
diff --git a/examples/linux/README b/examples/linux/README new file mode 100644 index 0000000..d138018 --- /dev/null +++ b/examples/linux/README @@ -0,0 +1,19 @@ +A more detailed version of this quickstart is available at: + +http://qgroundcontrol.org/dev/mavlink_linux_integration_tutorial + +MAVLINK UDP QUICKSTART INSTRUCTIONS +=================================== + +MAVLink UDP Example for *nix system (Linux, MacOS, BSD, etc.) + +To compile with GCC, just enter: + +gcc -I ../../include/common -o mavlink_udp mavlink_udp.c + +To run, type: + +./mavlink_udp + + +If you run QGroundControl on the same machine, a MAV should pop up. diff --git a/examples/linux/mavlink_udp.c b/examples/linux/mavlink_udp.c new file mode 100644 index 0000000..6f4ce7c --- /dev/null +++ b/examples/linux/mavlink_udp.c @@ -0,0 +1,213 @@ +/******************************************************************************* + 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 . + + ****************************************************************************/ +/* + 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 sucessfully 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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if (defined __QNX__) | (defined __QNXNTO__) +/* QNX specific headers */ +#include +#else +/* Linux / MacOS POSIX timer headers */ +#include +#include +#include +#endif + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ +#include + + +#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; + 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(" \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 (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0) + { + 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); + 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 diff --git a/mavgenerate.py b/mavgenerate.py new file mode 100755 index 0000000..8c2d2c9 --- /dev/null +++ b/mavgenerate.py @@ -0,0 +1,196 @@ +#!/usr/bin/env python +"""\ +generate.py is a GUI front-end for mavgen, a python based MAVLink +header generation tool. + +Notes: +----- +* 2012-7-16 -- dagoodman + Working on Mac 10.6.8 darwin, with Python 2.7.1 + +* 2012-7-17 -- dagoodman + Only GUI code working on Mac 10.6.8 darwin, with Python 3.2.3 + Working on Windows 7 SP1, with Python 2.7.3 and 3.2.3 + Mavgen doesn't work with Python 3.x yet + +* 2012-9-25 -- dagoodman + Passing error limit into mavgen to make output cleaner. + +Copyright 2012 David Goodman (dagoodman@soe.ucsc.edu) +Released under GNU GPL version 3 or later + +""" +import os +import re + +# Python 2.x and 3.x compatibility +try: + from tkinter import * + import tkinter.filedialog + import tkinter.messagebox +except ImportError as ex: + # Must be using Python 2.x, import and rename + from Tkinter import * + import tkFileDialog + import tkMessageBox + + tkinter.filedialog = tkFileDialog + del tkFileDialog + tkinter.messagebox = tkMessageBox + del tkMessageBox + +from pymavlink.generator import mavgen +from pymavlink.generator import mavparse + +title = "MAVLink Generator" +error_limit = 5 + + +class Application(Frame): + def __init__(self, master=None): + Frame.__init__(self, master) + self.pack_propagate(0) + self.grid( sticky=N+S+E+W) + self.createWidgets() + + """\ + Creates the gui and all of its content. + """ + def createWidgets(self): + + + #---------------------------------------- + # Create the XML entry + + self.xml_value = StringVar() + self.xml_label = Label( self, text="XML" ) + self.xml_label.grid(row=0, column = 0) + self.xml_entry = Entry( self, width = 26, textvariable=self.xml_value ) + self.xml_entry.grid(row=0, column = 1) + self.xml_button = Button (self, text="Browse", command=self.browseXMLFile) + self.xml_button.grid(row=0, column = 2) + + #---------------------------------------- + # Create the Out entry + + self.out_value = StringVar() + self.out_label = Label( self, text="Out" ) + self.out_label.grid(row=1,column = 0) + self.out_entry = Entry( self, width = 26, textvariable=self.out_value ) + self.out_entry.grid(row=1, column = 1) + self.out_button = Button (self, text="Browse", command=self.browseOutDirectory) + self.out_button.grid(row=1, column = 2) + + #---------------------------------------- + # Create the Lang box + + self.language_value = StringVar() + self.language_choices = mavgen.supportedLanguages + self.language_label = Label( self, text="Language" ) + self.language_label.grid(row=2, column=0) + self.language_menu = OptionMenu(self,self.language_value,*self.language_choices) + self.language_value.set(mavgen.DEFAULT_LANGUAGE) + self.language_menu.config(width=10) + self.language_menu.grid(row=2, column=1,sticky=W) + + #---------------------------------------- + # Create the Protocol box + + self.protocol_value = StringVar() + self.protocol_choices = [mavparse.PROTOCOL_0_9, mavparse.PROTOCOL_1_0] + self.protocol_label = Label( self, text="Protocol") + self.protocol_label.grid(row=3, column=0) + self.protocol_menu = OptionMenu(self,self.protocol_value,*self.protocol_choices) + self.protocol_value.set(mavgen.DEFAULT_WIRE_PROTOCOL) + self.protocol_menu.config(width=10) + self.protocol_menu.grid(row=3, column=1,sticky=W) + + #---------------------------------------- + # Create the Validate box + + self.validate_value = BooleanVar() + self.validate_label = Label( self, text="Validate") + self.validate_label.grid(row=4, column=0) + self.validate_button = Checkbutton(self, variable=self.validate_value, onvalue=True, offvalue=False) + self.validate_value.set(mavgen.DEFAULT_VALIDATE) + self.validate_button.config(width=10) + self.validate_button.grid(row=4, column=1,sticky=W) + + #---------------------------------------- + # Create the generate button + + self.generate_button = Button ( self, text="Generate", command=self.generateHeaders) + self.generate_button.grid(row=5,column=1) + + """\ + Open a file selection window to choose the XML message definition. + """ + def browseXMLFile(self): + # TODO Allow specification of multiple XML definitions + xml_file = tkinter.filedialog.askopenfilename(parent=self, title='Choose a definition file') + if xml_file != None: + self.xml_value.set(xml_file) + + """\ + Open a directory selection window to choose an output directory for + headers. + """ + def browseOutDirectory(self): + mavlinkFolder = os.path.dirname(os.path.realpath(__file__)) + out_dir = tkinter.filedialog.askdirectory(parent=self,initialdir=mavlinkFolder,title='Please select an output directory') + if out_dir != None: + self.out_value.set(out_dir) + + """\ + Generates the header files and place them in the output directory. + """ + def generateHeaders(self): + # Verify settings + rex = re.compile(".*\\.xml$", re.IGNORECASE) + if not self.xml_value.get(): + tkinter.messagebox.showerror('Error Generating Headers','An XML message definition file must be specified.') + return + + if not self.out_value.get(): + tkinter.messagebox.showerror('Error Generating Headers', 'An output directory must be specified.') + return + + + if os.path.isdir(self.out_value.get()): + if not tkinter.messagebox.askokcancel('Overwrite Headers?','The output directory \'{0}\' already exists. Headers may be overwritten if they already exist.'.format(self.out_value.get())): + return + + # Generate headers + opts = mavgen.Opts(self.out_value.get(), wire_protocol=self.protocol_value.get(), language=self.language_value.get(), validate=self.validate_value.get(), error_limit=error_limit); + args = [self.xml_value.get()] + try: + mavgen.mavgen(opts,args) + tkinter.messagebox.showinfo('Successfully Generated Headers', 'Headers generated successfully.') + + except Exception as ex: + exStr = formatErrorMessage(str(ex)); + tkinter.messagebox.showerror('Error Generating Headers','{0!s}'.format(exStr)) + return + +"""\ +Format the mavgen exceptions by removing 'ERROR: '. +""" +def formatErrorMessage(message): + reObj = re.compile(r'^(ERROR):\s+',re.M); + matches = re.findall(reObj, message); + prefix = ("An error occurred in mavgen:" if len(matches) == 1 else "Errors occurred in mavgen:\n") + message = re.sub(reObj, '\n', message); + + return prefix + message + + +# End of Application class +# --------------------------------- + +# --------------------------------- +# Start + +if __name__ == '__main__': + app = Application() + app.master.title(title) + app.mainloop() diff --git a/message_definitions/v0.9/ardupilotmega.xml b/message_definitions/v0.9/ardupilotmega.xml new file mode 100644 index 0000000..6733531 --- /dev/null +++ b/message_definitions/v0.9/ardupilotmega.xml @@ -0,0 +1,270 @@ + + + common.xml + + + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + + + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch(deg*100) or lat, depending on mount mode. + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + Empty + Empty + Empty + Empty + + + + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached minimum altitude + + + Breached fence boundary + + + + + + + Offsets and calibrations values for hardware + sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + + Configure on-board Camera Control System. + System ID + Component ID + Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + Exposure type enumeration from 1 to N (0 means ignore) + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + Control on-board Camera Control System to take shots. + System ID + Component ID + 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + 1 to N //Zoom's absolute position (0 means ignore) + -100 to 100 //Zooming step value to offset zoom from the current position + 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + 0: ignore, 1: shot or start filming + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + + Message to configure a camera mount, directional antenna, etc. + System ID + Component ID + mount operating mode (see MAV_MOUNT_MODE enum) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + + + + Message to control a camera mount, directional antenna, etc. + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + + + + Message with some status from APM to GCS about camera or antenna mount + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + + + + + A fence point. Used to set a point when from + GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 1, 0 is for return point) + total number of points (for sanity checking) + Latitude of point + Longitude of point + + + + Request a current fence point from MAV + System ID + Component ID + point index (first point is 1, 0 is for return point) + + + + Status of geo-fencing. Sent in extended + status stream when fencing enabled + 0 if currently inside fence, 1 if outside + number of fence breaches + last breach type (see FENCE_BREACH_* enum) + time of last breach in milliseconds since boot + + + + Status of DCM attitude estimator + X gyro drift estimate rad/s + Y gyro drift estimate rad/s + Z gyro drift estimate rad/s + average accel_weight + average renormalisation value + average error_roll_pitch value + average error_yaw value + + + + Status of simulation environment, if used + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + + + + Status of key hardware + board voltage (mV) + I2C error count + + + + Status generated by radio + local signal strength + remote signal strength + how full the tx buffer is as a percentage + background noise level + remote background noise level + receive errors + count of error corrected packets + + + diff --git a/message_definitions/v0.9/common.xml b/message_definitions/v0.9/common.xml new file mode 100644 index 0000000..dd4ea84 --- /dev/null +++ b/message_definitions/v0.9/common.xml @@ -0,0 +1,941 @@ + + + 2 + + + Commands to be executed by the MAV. They can be executed on user request, + or as part of a mission script. If the action is used in a mission, the parameter mapping + to the waypoint/mission message is as follows: + Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what + ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to waypoint. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at waypoint (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this waypoint an unlimited amount of time + Empty + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X turns + Turns + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X seconds + Seconds (decimal) + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Empty + Empty + Empty + Desired yaw angle. + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Empty + Empty + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + Empty + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Control onboard camera capturing. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + + Region of interest mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple cameras etc.) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Empty + Empty + Empty + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Reserved + Reserved + Empty + Empty + Empty + + + + Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + + No region of interest. + + + Point toward next waypoint. + + + Point toward given waypoint. + + + Point toward fixed location. + + + Point toward of given id. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. + The onboard software version + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + Unix timestamp in microseconds + + + UTC date and time from GPS module + GPS UTC date ddmmyy + GPS UTC time hhmmss + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The action id + 0: Action DENIED, 1: Action executed + + + An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The system executing the action + The component executing the action + The action id + + + Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new mode + + + Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components. + The system setting the mode + The new navigation mode + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id + Parameter index. Send -1 to use the param ID field as identifier + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id + Onboard parameter value + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id + Onboard parameter value + + + The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in 1E7 degrees + Longitude in 1E7 degrees + Altitude in 1E3 meters (millimeters) + GPS HDOP + GPS VDOP + GPS ground speed (m/s) + Compass heading in degrees, 0..360 degrees + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw) + Differential pressure 2 (raw) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since unix epoch) + Latitude, in degrees + Longitude, in degrees + Absolute altitude, in meters + X Speed (in Latitude direction, positive: going north) + Y Speed (in Longitude direction, positive: going east) + Z Speed (in Altitude direction, positive: going up) + + + The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in degrees + Longitude in degrees + Altitude in meters + GPS HDOP + GPS VDOP + GPS ground speed + Compass heading in degrees, 0..360 degrees + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + Navigation mode, see MAV_NAV_MODE ENUM + System status flag, see MAV_STATUS ENUM + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Remaining battery energy: (0%: 0, 100%: 1000) + Dropped packets (packets that were corrupted on reception on the MAV) + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + Receive signal strength indicator, 0: 0%, 255: 100% + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed + System ID + Component ID + Sequence + The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude + + + Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message. + System ID + Component ID + Sequence + + + Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint. + Sequence + + + Request the overall list of waypoints from the system/component. + System ID + Component ID + + + This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints. + System ID + Component ID + Number of Waypoints in the Sequence + + + Delete all waypoints at once. + System ID + Component ID + + + A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. + Sequence + + + Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + 0: OK, 1: Error + + + As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Component ID + global position * 1E7 + global position * 1E7 + global position * 1000 + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), expressed as * 1E7 + Longitude (WGS84), expressed as * 1E7 + Altitude(WGS84), expressed as * 1000 + + + Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. + System ID + Component ID + x position + y position + z position + Desired yaw angle + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + x position + y position + z position + Desired yaw angle + + + Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + Attitude estimation health: 0: poor, 255: excellent + 0: Attitude control disabled, 1: enabled + 0: X, Y position control disabled, 1: enabled + 0: Z position control disabled, 1: enabled + 0: Yaw angle control disabled, 1: enabled + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + Collective thrust, normalized to 0 .. 1 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + Collective thrust, normalized to 0 .. 1 + + + Setpoint in roll, pitch, yaw currently active on the system. + Timestamp in micro seconds since unix epoch + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + Collective thrust, normalized to 0 .. 1 + + + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system. + Timestamp in micro seconds since unix epoch + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + Collective thrust, normalized to 0 .. 1 + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs +of the controller before actual flight and to assist with tuning controller parameters + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current waypoint/target in degrees + Distance to active waypoint in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint. + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. + x position error + y position error + z position error + roll error (radians) + pitch error (radians) + yaw error (radians) + x velocity + y velocity + z velocity + + + The system setting the altitude + The new altitude in meters + + + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested message type + Update rate in Hertz + 1 to start sending, 0 to stop sending. + + + This packet is useful for high throughput + applications such as hardware in the loop simulations. + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -3 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Send a command with up to four parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed + Current airspeed in m/s + 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels in x-sensor direction + Flow in pixels in y-sensor direction + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters + + + Object has been detected + Timestamp in milliseconds since system boot + Object ID + Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal + Name of the object as defined by the detector + Detection quality / confidence. 0: bad, 255: maximum confidence + Angle of the object with respect to the body frame in NED coordinates in radians. 0: front + Ground distance in meters + + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status, 0 = info message, 255 = critical fault + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + index of debug variable + DEBUG value + + + diff --git a/message_definitions/v0.9/minimal.xml b/message_definitions/v0.9/minimal.xml new file mode 100644 index 0000000..5b41a49 --- /dev/null +++ b/message_definitions/v0.9/minimal.xml @@ -0,0 +1,13 @@ + + + 2 + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + diff --git a/message_definitions/v0.9/slugs.xml b/message_definitions/v0.9/slugs.xml new file mode 100644 index 0000000..db08abb --- /dev/null +++ b/message_definitions/v0.9/slugs.xml @@ -0,0 +1,148 @@ + + + common.xml + + + + + + + + Sensor and DSC control loads. + + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + + Air data for altitude and airspeed computation. + + Dynamic pressure (Pa) + Static pressure (Pa) + Board temperature + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the Nav Filter + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Visible sattelites reported by Gps + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + The system setting the commands + Commanded Airspeed + Log value 2 + Log value 3 + + + + + This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + The system setting the commands + Bitfield containing the PT configuration + + + + + + Action messages focused on the SLUGS AP. + The system reporting the action + Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + Value associated with the action + + + + diff --git a/message_definitions/v0.9/test.xml b/message_definitions/v0.9/test.xml new file mode 100644 index 0000000..43a11e3 --- /dev/null +++ b/message_definitions/v0.9/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/message_definitions/v0.9/ualberta.xml b/message_definitions/v0.9/ualberta.xml new file mode 100644 index 0000000..4023aa9 --- /dev/null +++ b/message_definitions/v0.9/ualberta.xml @@ -0,0 +1,54 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + Raw input pulse widts sent to output + Inputs are normalized using calibration, the converted back to raw pulse widths for output + dfsdfs + dfsfds + dfsdfsdfs + + + Navigation filter mode + + AHRS mode + INS/GPS initialization mode + INS/GPS mode + + + Mode currently commanded by pilot + sdf + dfs + Rotomotion mode + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/message_definitions/v1.0/ASLUAV.xml b/message_definitions/v1.0/ASLUAV.xml new file mode 100644 index 0000000..0c3e394 --- /dev/null +++ b/message_definitions/v1.0/ASLUAV.xml @@ -0,0 +1,176 @@ + + + + + common.xml + + + + + Mission command to reset Maximum Power Point Tracker (MPPT) + MPPT number + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a power cycle on payload + Complete power cycle + VISensor power cycle + Empty + Empty + Empty + Empty + Empty + + + + + + Voltage and current sensor data + Power board voltage sensor reading in volts + Power board current sensor reading in amps + Board current sensor 1 reading in amps + Board current sensor 2 reading in amps + + + Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking + MPPT last timestamp + MPPT1 voltage + MPPT1 current + MPPT1 pwm + MPPT1 status + MPPT2 voltage + MPPT2 current + MPPT2 pwm + MPPT2 status + MPPT3 voltage + MPPT3 current + MPPT3 pwm + MPPT3 status + + + ASL-fixed-wing controller data + Timestamp + ASLCTRL control-mode (manual, stabilized, auto, etc...) + See sourcecode for a description of these values... + + + Pitch angle [deg] + Pitch angle reference[deg] + + + + + + + Airspeed reference [m/s] + + Yaw angle [deg] + Yaw angle reference[deg] + Roll angle [deg] + Roll angle reference[deg] + + + + + + + + + ASL-fixed-wing controller debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + + + Extended state information for ASLUAVs + Status of the position-indicator LEDs + Status of the IRIDIUM satellite communication system + Status vector for up to 8 servos + Motor RPM + + + + Extended EKF state estimates for ASLUAVs + Time since system start [us] + Magnitude of wind velocity (in lateral inertial plane) [m/s] + Wind heading angle from North [rad] + Z (Down) component of inertial wind velocity [m/s] + Magnitude of air velocity [m/s] + Sideslip angle [rad] + Angle of attack [rad] + + + Off-board controls/commands for ASLUAVs + Time since system start [us] + Elevator command [~] + Throttle command [~] + Throttle 2 command [~] + Left aileron command [~] + Right aileron command [~] + Rudder command [~] + Off-board computer status + + + Atmospheric sensors (temperature, humidity, ...) + Ambient temperature [degrees Celsius] + Relative humidity [%] + + + Battery pack monitoring data for Li-Ion batteries + Battery pack temperature in [deg C] + Battery pack voltage in [mV] + Battery pack current in [mA] + Battery pack state-of-charge + Battery monitor status report bits in Hex + Battery monitor serial number in Hex + Battery monitor sensor host FET control in Hex + Battery pack cell 1 voltage in [mV] + Battery pack cell 2 voltage in [mV] + Battery pack cell 3 voltage in [mV] + Battery pack cell 4 voltage in [mV] + Battery pack cell 5 voltage in [mV] + Battery pack cell 6 voltage in [mV] + + + Fixed-wing soaring (i.e. thermal seeking) data + Timestamp [ms] + Timestamp since last mode change[ms] + Updraft speed at current/local airplane position [m/s] + Thermal core updraft strength [m/s] + Thermal radius [m] + Thermal center latitude [deg] + Thermal center longitude [deg] + Variance W + Variance R + Variance Lat + Variance Lon + Suggested loiter radius [m] + Control Mode [-] + Data valid [-] + + + Monitoring of sensorpod status + Timestamp in linuxtime [ms] (since 1.1.1970) + Rate of ROS topic 1 + Rate of ROS topic 2 + Rate of ROS topic 3 + Rate of ROS topic 4 + Number of recording nodes + Temperature of sensorpod CPU in [deg C] + Free space available in recordings directory in [Gb] * 1e2 + + + diff --git a/message_definitions/v1.0/ardupilotmega.xml b/message_definitions/v1.0/ardupilotmega.xml new file mode 100644 index 0000000..e04c0b1 --- /dev/null +++ b/message_definitions/v1.0/ardupilotmega.xml @@ -0,0 +1,1564 @@ + + + common.xml + + + + + + Mission command to perform motor test + motor sequence number (a number from 1 to max number of motors on the vehicle) + throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) + throttle + timeout (in seconds) + Empty + Empty + Empty + + + + Mission command to operate EPM gripper + gripper number (a number from 1 to max number of grippers on the vehicle) + gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum) + Empty + Empty + Empty + Empty + Empty + + + + Enable/disable autotune + enable (1: enable, 0:disable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. + altitude (m) + descent speed (m/s) + Wiggle Time (s) + Empty + Empty + Empty + Empty + + + + A system wide power-off event has been initiated. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + FLY button has been clicked. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + FLY button has been held for 1.5 seconds. + Takeoff altitude + Empty + Empty + Empty + Empty + Empty + Empty + + + + PAUSE button has been clicked. + 1 if Solo is in a shot mode, 0 otherwise + Empty + Empty + Empty + Empty + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Automatically retry on failure (0=no retry, 1=retry). + Save without user input (0=require input, 1=autosave). + Delay (seconds) + Autoreboot (0=user reboot, 1=autoreboot) + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Cancel a running magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reply with the version banner + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Causes the gimbal to reset and boot as if it was just powered on + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Command autopilot to get into factory test/diagnostic mode + 0 means get out of test mode, 1 means get into test mode + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reports progress and success or failure of gimbal axis calibration procedure + Gimbal axis we're reporting calibration progress for + Current calibration progress for this axis, 0x64=100% + Status of the calibration + Empty + Empty + Empty + Empty + + + + Starts commutation calibration on the gimbal + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Erases gimbal application and parameters + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + a limit has been breached + + + + taking action eg. RTL + + + + we're no longer in breach of a limit + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + + + Flags in RALLY_POINT message + + Flag set when requiring favorable winds for landing. + + + + Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. + + + + + + + Disable parachute release + + + + Enable parachute release + + + + Release parachute + + + + + + + throttle as a percentage from 0 ~ 100 + + + + throttle as an absolute PWM value (normally in range of 1000~2000) + + + + throttle pass-through from pilot's transmitter + + + + + + Gripper actions. + + gripper release of cargo + + + + gripper grabs onto cargo + + + + + + + Camera heartbeat, announce camera component ID at 1hz + + + + Camera image triggered + + + + Camera connection lost + + + + Camera unknown error + + + + Camera battery low. Parameter p1 shows reported voltage + + + + Camera storage low. Parameter p1 shows reported shots remaining + + + + Camera storage low. Parameter p1 shows reported video minutes remaining + + + + + + + Shooting photos, not video + + + + Shooting video, not stills + + + + Unable to achieve requested exposure (e.g. shutter speed too low) + + + + Closed loop feedback from camera, we know for sure it has successfully taken a picture + + + + Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture + + + + + + + Gimbal is powered on but has not started initializing yet + + + + Gimbal is currently running calibration on the pitch axis + + + + Gimbal is currently running calibration on the roll axis + + + + Gimbal is currently running calibration on the yaw axis + + + + Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter + + + + Gimbal is actively stabilizing + + + + Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command + + + + + + Gimbal yaw axis + + + + Gimbal pitch axis + + + + Gimbal roll axis + + + + + + Axis calibration is in progress + + + + Axis calibration succeeded + + + + Axis calibration failed + + + + + + Whether or not this axis requires calibration is unknown at this time + + + + This axis requires calibration + + + + This axis does not require calibration + + + + + + + No GoPro connected + + + + The detected GoPro is not HeroBus compatible + + + + A HeroBus compatible GoPro is connected + + + + An unrecoverable error was encountered with the connected GoPro, it may require a power cycle + + + + + + + GoPro is currently recording + + + + + + The write message with ID indicated succeeded + + + + The write message with ID indicated failed + + + + + + (Get/Set) + + + + (Get/Set) + + + + (___/Set) + + + + (Get/___) + + + + (Get/___) + + + + (Get/Set) + + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) + + + + + (Get/Set) + + + + + + Video mode + + + + Photo mode + + + + Burst mode, hero 3+ only + + + + Time lapse mode, hero 3+ only + + + + Multi shot mode, hero 4 only + + + + Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black + + + + Playback mode, hero 4 only + + + + Mode not yet known + + + + + + 848 x 480 (480p) + + + + 1280 x 720 (720p) + + + + 1280 x 960 (960p) + + + + 1920 x 1080 (1080p) + + + + 1920 x 1440 (1440p) + + + + 2704 x 1440 (2.7k-17:9) + + + + 2704 x 1524 (2.7k-16:9) + + + + 2704 x 2028 (2.7k-4:3) + + + + 3840 x 2160 (4k-16:9) + + + + 4096 x 2160 (4k-17:9) + + + + 1280 x 720 (720p-SuperView) + + + + 1920 x 1080 (1080p-SuperView) + + + + 2704 x 1520 (2.7k-SuperView) + + + + 3840 x 2160 (4k-SuperView) + + + + + + 12 FPS + + + + 15 FPS + + + + 24 FPS + + + + 25 FPS + + + + 30 FPS + + + + 48 FPS + + + + 50 FPS + + + + 60 FPS + + + + 80 FPS + + + + 90 FPS + + + + 100 FPS + + + + 120 FPS + + + + 240 FPS + + + + 12.5 FPS + + + + + + 0x00: Wide + + + + 0x01: Medium + + + + 0x02: Narrow + + + + + + 0=NTSC, 1=PAL + + + + + + 5MP Medium + + + + 7MP Medium + + + + 7MP Wide + + + + 10MP Wide + + + + 12MP Wide + + + + + + Auto + + + + 3000K + + + + 5500K + + + + 6500K + + + + Camera Raw + + + + + + Auto + + + + Neutral + + + + + + ISO 400 + + + + ISO 800 (Only Hero 4) + + + + ISO 1600 + + + + ISO 3200 (Only Hero 4) + + + + ISO 6400 + + + + + + Low Sharpness + + + + Medium Sharpness + + + + High Sharpness + + + + + + -5.0 EV (Hero 3+ Only) + + + + -4.5 EV (Hero 3+ Only) + + + + -4.0 EV (Hero 3+ Only) + + + + -3.5 EV (Hero 3+ Only) + + + + -3.0 EV (Hero 3+ Only) + + + + -2.5 EV (Hero 3+ Only) + + + + -2.0 EV + + + + -1.5 EV + + + + -1.0 EV + + + + -0.5 EV + + + + 0.0 EV + + + + +0.5 EV + + + + +1.0 EV + + + + +1.5 EV + + + + +2.0 EV + + + + +2.5 EV (Hero 3+ Only) + + + + +3.0 EV (Hero 3+ Only) + + + + +3.5 EV (Hero 3+ Only) + + + + +4.0 EV (Hero 3+ Only) + + + + +4.5 EV (Hero 3+ Only) + + + + +5.0 EV (Hero 3+ Only) + + + + + + Charging disabled + + + + Charging enabled + + + + + + Unknown gopro model + + + + Hero 3+ Silver (HeroBus not supported by GoPro) + + + + Hero 3+ Black + + + + Hero 4 Silver + + + + Hero 4 Black + + + + + + 3 Shots / 1 Second + + + + 5 Shots / 1 Second + + + + 10 Shots / 1 Second + + + + 10 Shots / 2 Second + + + + 10 Shots / 3 Second (Hero 4 Only) + + + + 30 Shots / 1 Second + + + + 30 Shots / 2 Second + + + + 30 Shots / 3 Second + + + + 30 Shots / 6 Second + + + + + + + LED patterns off (return control to regular vehicle control) + + + + LEDs show pattern during firmware update + + + + Custom Pattern using custom bytes fields + + + + + + Flags in EKF_STATUS message + + set if EKF's attitude estimate is good + + + + set if EKF's horizontal velocity estimate is good + + + + set if EKF's vertical velocity estimate is good + + + + set if EKF's horizontal position (relative) estimate is good + + + + set if EKF's horizontal position (absolute) estimate is good + + + + set if EKF's vertical position (absolute) estimate is good + + + + set if EKF's vertical position (above ground) estimate is good + + + + EKF is in constant position mode and does not know it's absolute or relative position + + + + set if EKF's predicted horizontal position (relative) estimate is good + + + + set if EKF's predicted horizontal position (absolute) estimate is good + + + + + + + + + + + + + + + + + + + + + + Special ACK block numbers control activation of dataflash log streaming + + + + UAV to stop sending DataFlash blocks + + + + + UAV to start sending DataFlash blocks + + + + + + + Possible remote log data block statuses + + This block has NOT been received + + + + This block has been received + + + + + + + Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + + Configure on-board Camera Control System. + System ID + Component ID + Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + Exposure type enumeration from 1 to N (0 means ignore) + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + Control on-board Camera Control System to take shots. + System ID + Component ID + 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + 1 to N //Zoom's absolute position (0 means ignore) + -100 to 100 //Zooming step value to offset zoom from the current position + 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + 0: ignore, 1: shot or start filming + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + + Message to configure a camera mount, directional antenna, etc. + System ID + Component ID + mount operating mode (see MAV_MOUNT_MODE enum) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + + + + Message to control a camera mount, directional antenna, etc. + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + + + + Message with some status from APM to GCS about camera or antenna mount + System ID + Component ID + pitch(deg*100) + roll(deg*100) + yaw(deg*100) + + + + + A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 1, 0 is for return point) + total number of points (for sanity checking) + Latitude of point + Longitude of point + + + + Request a current fence point from MAV + System ID + Component ID + point index (first point is 1, 0 is for return point) + + + + Status of geo-fencing. Sent in extended status stream when fencing enabled + 0 if currently inside fence, 1 if outside + number of fence breaches + last breach type (see FENCE_BREACH_* enum) + time of last breach in milliseconds since boot + + + + Status of DCM attitude estimator + X gyro drift estimate rad/s + Y gyro drift estimate rad/s + Z gyro drift estimate rad/s + average accel_weight + average renormalisation value + average error_roll_pitch value + average error_yaw value + + + + Status of simulation environment, if used + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + Status of key hardware + board voltage (mV) + I2C error count + + + + Status generated by radio + local signal strength + remote signal strength + how full the tx buffer is as a percentage + background noise level + remote background noise level + receive errors + count of error corrected packets + + + + + Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled + state of AP_Limits, (see enum LimitState, LIMITS_STATE) + time of last breach in milliseconds since boot + time of last recovery action in milliseconds since boot + time of last successful recovery in milliseconds since boot + time of last all-clear in milliseconds since boot + number of fence breaches + AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) + + + + Wind estimation + wind direction that wind is coming from (degrees) + wind speed in ground plane (m/s) + vertical wind speed (m/s) + + + + Data packet, size 16 + data type + data length + raw data + + + + Data packet, size 32 + data type + data length + raw data + + + + Data packet, size 64 + data type + data length + raw data + + + + Data packet, size 96 + data type + data length + raw data + + + + Rangefinder reporting + distance in meters + raw voltage if available, zero otherwise + + + + Airspeed auto-calibration + GPS velocity north m/s + GPS velocity east m/s + GPS velocity down m/s + Differential pressure pascals + Estimated to true airspeed ratio + Airspeed ratio + EKF state x + EKF state y + EKF state z + EKF Pax + EKF Pby + EKF Pcz + + + + + A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 0) + total number of points (for sanity checking) + Latitude of point in degrees * 1E7 + Longitude of point in degrees * 1E7 + Transit / loiter altitude in meters relative to home + + Break altitude in meters relative to home + Heading to aim for when landing. In centi-degrees. + See RALLY_FLAGS enum for definition of the bitmask. + + + + Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. + System ID + Component ID + point index (first point is 0) + + + + Status of compassmot calibration + throttle (percent*10) + current (amps) + interference (percent) + Motor Compensation X + Motor Compensation Y + Motor Compensation Z + + + + + Status of secondary AHRS filter if available + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + + Camera Event + Image timestamp (microseconds since UNIX epoch, according to camera clock) + System ID + + Camera ID + + Image index + + See CAMERA_STATUS_TYPES enum for definition of the bitmask + Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + + + + + Camera Capture Feedback + Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) + System ID + + Camera ID + + Image index + + Latitude in (deg * 1E7) + Longitude in (deg * 1E7) + Altitude Absolute (meters AMSL) + Altitude Relative (meters above HOME location) + Camera Roll angle (earth frame, degrees, +-180) + + Camera Pitch angle (earth frame, degrees, +-180) + + Camera Yaw (earth frame, degrees, 0-360, true) + + Focal Length (mm) + + See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + + + + + 2nd Battery status + voltage in millivolts + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + + + + Status of third AHRS filter if available. This is for ANU research group (Ali and Sean) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + test variable1 + test variable2 + test variable3 + test variable4 + + + + Request the autopilot version from the system/component. + System ID + Component ID + + + + + Send a block of log data to remote location + System ID + Component ID + log data block sequence number + log data block + + + + Send Status of each log block that autopilot board might have sent + System ID + Component ID + log data block sequence number + log data block status + + + + Control vehicle LEDs + System ID + Component ID + Instance (LED instance to control or 255 for all LEDs) + Pattern (see LED_PATTERN_ENUM) + Custom Byte Length + Custom Bytes + + + + Reports progress of compass calibration. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + Attempt number + Completion percentage + Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid) + Body frame direction vector for display + Body frame direction vector for display + Body frame direction vector for display + + + + Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters + RMS milligauss residuals + X offset + Y offset + Z offset + X diagonal (matrix 11) + Y diagonal (matrix 22) + Z diagonal (matrix 33) + X off-diagonal (matrix 12 and 21) + Y off-diagonal (matrix 13 and 31) + Z off-diagonal (matrix 32 and 23) + + + + + EKF Status message including flags and variances + Flags + + Velocity variance + + Horizontal Position variance + Vertical Position variance + Compass variance + Terrain Altitude variance + + + + + PID tuning information + axis + desired rate (degrees/s) + achieved rate (degrees/s) + FF component + P component + I component + D component + + + + 3 axis gimbal mesuraments + System ID + Component ID + Time since last update (seconds) + Delta angle X (radians) + Delta angle Y (radians) + Delta angle X (radians) + Delta velocity X (m/s) + Delta velocity Y (m/s) + Delta velocity Z (m/s) + Joint ROLL (radians) + Joint EL (radians) + Joint AZ (radians) + + + + Control message for rate gimbal + System ID + Component ID + Demanded angular rate X (rad/s) + Demanded angular rate Y (rad/s) + Demanded angular rate Z (rad/s) + + + + 100 Hz gimbal torque command telemetry + System ID + Component ID + Roll Torque Command + Elevation Torque Command + Azimuth Torque Command + + + + + Heartbeat from a HeroBus attached GoPro + Status + Current capture mode + additional status bits + + + + + Request a GOPRO_COMMAND response from the GoPro + System ID + Component ID + Command ID + + + + Response from a GOPRO_COMMAND get request + Command ID + Status + Value + + + + Request to set a GOPRO_COMMAND with a desired + System ID + Component ID + Command ID + Value + + + + Response from a GOPRO_COMMAND set request + Command ID + Status + + + + + RPM sensor output + RPM Sensor1 + RPM Sensor2 + + + diff --git a/message_definitions/v1.0/autoquad.xml b/message_definitions/v1.0/autoquad.xml new file mode 100644 index 0000000..8c22478 --- /dev/null +++ b/message_definitions/v1.0/autoquad.xml @@ -0,0 +1,169 @@ + + + common.xml + 3 + + + Track current version of these definitions (can be used by checking value of AUTOQUAD_MAVLINK_DEFS_VERSION_ENUM_END). Append a new entry for each published change. + + + + Available operating modes/statuses for AutoQuad flight controller. + Bitmask up to 32 bits. Low side bits for base modes, high side for + additional active features/modifiers/constraints. + + System is initializing + + + + System is *armed* and standing by, with no throttle input and no autonomous mode + + + Flying (throttle input detected), assumed under manual control unless other mode bits are set + + + Altitude hold engaged + + + Position hold engaged + + + Externally-guided (eg. GCS) navigation mode + + + Autonomous mission execution mode + + + + Ready but *not armed* + + + Calibration mode active + + + + No valid control input (eg. no radio link) + + + Battery is low (stage 1 warning) + + + Battery is depleted (stage 2 warning) + + + + Dynamic Velocity Hold is active (PH with proportional manual direction override) + + + ynamic Altitude Override is active (AH with proportional manual adjustment) + + + + Craft is at ceiling altitude + + + Ceiling altitude is set + + + Heading-Free dynamic mode active + + + Heading-Free locked mode active + + + Automatic Return to Home is active + + + System is in failsafe recovery mode + + + + + Orbit a waypoint. + Orbit radius in meters + Loiter time in decimal seconds + Maximum horizontal speed in m/s + Desired yaw angle at waypoint + Latitude + Longitude + Altitude + + + Start/stop AutoQuad telemetry values stream. + Start or stop (1 or 0) + Stream frequency in us + Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code) + Empty + Empty + Empty + Empty + + + + Request AutoQuad firmware version number. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + + Motor/ESC telemetry data. + + + + + + Sends up to 20 raw float values. + Index of message + value1 + value2 + value3 + value4 + value5 + value6 + value7 + value8 + value9 + value10 + value11 + value12 + value13 + value14 + value15 + value16 + value17 + value18 + value19 + value20 + + + Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has > 4 motors. Data is described as follows: + // unsigned int state : 3; + // unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - + // unsigned int errors : 9; // Bad detects error count + // - Data Version 3 - + // unsigned int temp : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + + Timestamp of the component clock since boot time in ms. + Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc). + Total number of active ESCs/motors on the system. + Number of active ESCs in this sequence (1 through this many array members will be populated with data) + ESC/Motor ID + Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data. + Version of data structure (determines contents). + Data bits 1-32 for each ESC. + Data bits 33-64 for each ESC. + + + diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml new file mode 100644 index 0000000..a055de9 --- /dev/null +++ b/message_definitions/v1.0/common.xml @@ -0,0 +1,3347 @@ + + + 3 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + Reserved for future use. + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + PX4 Autopilot - http://pixhawk.ethz.ch/px4/ + + + SMACCMPilot - http://smaccmpilot.org + + + AutoQuad -- http://autoquad.org + + + Armazila -- http://armazila.com + + + Aerob -- http://aerob.ru + + + ASLUAV autopilot -- http://www.asl.ethz.ch + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + Flapping wing + + + Onboard companion controller + + + Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. + + + Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. + + + Tiltrotor VTOL + + + + VTOL reserved 2 + + + VTOL reserved 3 + + + VTOL reserved 4 + + + VTOL reserved 5 + + + Onboard gimbal + + + Onboard ADSB peripheral + + + + These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. + + development release + + + alpha release + + + beta release + + + release candidate + + + official stable release + + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + Override command, pauses current mission execution and moves immediately to a position + + Hold at the current position. + + + Continue with the next item in mission execution. + + + Hold at the current position of the system + + + Hold at the position specified in the parameters of the DO_HOLD action + + + + These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. + + System is not ready to fly, booting, calibrating, etc. No flag is set. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + On Screen Display (OSD) devices for video links + + + Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol + + + + These encode the sensors whose status is sent as part of the SYS_STATUS message. + + 0x01 3D gyro + + + 0x02 3D accelerometer + + + 0x04 3D magnetometer + + + 0x08 absolute pressure + + + 0x10 differential pressure + + + 0x20 GPS + + + 0x40 optical flow + + + 0x80 computer vision position + + + 0x100 laser based position + + + 0x200 external ground truth (Vicon or Leica) + + + 0x400 3D angular rate control + + + 0x800 attitude stabilization + + + 0x1000 yaw position + + + 0x2000 z/altitude control + + + 0x4000 x/y position control + + + 0x8000 motor outputs / control + + + 0x10000 rc receiver + + + 0x20000 2nd 3D gyro + + + 0x40000 2nd 3D accelerometer + + + 0x80000 2nd 3D magnetometer + + + 0x100000 geofence + + + 0x200000 AHRS subsystem health + + + 0x400000 Terrain subsystem health + + + 0x800000 Motors are reversed + + + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) + + + Local coordinate frame, Z-up (x: north, y: east, z: down). + + + NOT a coordinate frame, indicates a mission command. + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Local coordinate frame, Z-down (x: east, y: north, z: up) + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. + + + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + + + Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + + + + + + + + + + + + + + + + + + + + + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + Report fence breach, but don't take action + + + Switched to guided mode to return point (fence point 0) with manual throttle control + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached maximum altitude + + + Breached fence boundary + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + + + Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to MISSION. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at MISSION (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this MISSION an unlimited amount of time + Empty + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X turns + Turns + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X seconds + Seconds (decimal) + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Abort Alt + Empty + Empty + Desired yaw angle + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Land at local position (local frame only) + Landing target number (if available) + Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land + Landing descend rate [ms^-1] + Desired yaw angle [rad] + Y-axis position [m] + X-axis position [m] + Z-axis / ground level position [m] + + + Takeoff from local position (local frame only) + Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad] + Empty + Takeoff ascend rate [ms^-1] + Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these + Y-axis position [m] + X-axis position [m] + Z-axis position [m] + + + Vehicle following, i.e. this waypoint represents the position of a moving vehicle + Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation + Ground speed of vehicle to be followed + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. + Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. + Empty + Empty + Empty + Empty + Empty + Desired altitude in meters + + + Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. + Heading Required (0 = False) + Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. + Empty + Empty + Latitude + Longitude + Altitude + + + Being following a target + System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode + RESERVED + RESERVED + altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home + altitude + RESERVED + TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout + + + Reposition the MAV after a follow target command has been sent + Camera q1 (where 0 is on the ray from the camera to the tracking device) + Camera q2 + Camera q3 + Camera q4 + altitude offset from target (m) + X offset from target (m) + Y offset from target (m) + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Navigate to MISSION using a spline path. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Empty + Empty + Empty + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Takeoff from ground using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + Land using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + + + + hand control over to an external controller + On / Off (> 0.5f on) + Empty + Empty + Empty + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Custom mode - this is system specific, please refer to the individual autopilot specifications for details. + Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + Empty + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Terminate flight immediately + Flight termination activated if > 0.5 + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. + Empty + Empty + Empty + Empty + Latitude + Longitude + Empty + + + Mission command to perform a landing from a rally point. + Break altitude (meters) + Landing speed (m/s) + Empty + Empty + Empty + Empty + Empty + + + Mission command to safely abort an autonmous landing. + Altitude (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reposition the vehicle to a specific WGS84 global position. + Ground speed, less than 0 (-1) for default + Reserved + Reserved + Yaw heading, NaN for unchanged + Latitude (deg * 1E7) + Longitude (deg * 1E7) + Altitude (meters) + + + If in a GPS controlled position mode, hold the current position or continue. + 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Control onboard camera system. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch or lat in degrees, depending on mount mode. + roll or lon in degrees depending on mount mode + yaw or alt (in meters) depending on mount mode + reserved + reserved + reserved + MAV_MOUNT_MODE enum value + + + + Mission command to set CAM_TRIGG_DIST for this flight + Camera trigger distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to enable the geofence + enable? (0=disable, 1=enable, 2=disable_floor_only) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to trigger a parachute + action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Change to/from inverted flight + inverted (0=normal, 1=inverted) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount, using a quaternion as reference. + q1 - quaternion param #1, w (1 in null-rotation) + q2 - quaternion param #2, x (0 in null-rotation) + q3 - quaternion param #3, y (0 in null-rotation) + q4 - quaternion param #4, z (0 in null-rotation) + Empty + Empty + Empty + + + + set id of master controller + System ID + Component ID + Empty + Empty + Empty + Empty + Empty + + + + set limits for external control + timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout + absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit + absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit + horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit + Empty + Empty + Empty + + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Accelerometer calibration: 0: no, 1: yes + Compass/Motor interference calibration: 0: no, 1: yes + Empty + + + Set sensor offsets. This command will be only accepted if in pre-flight mode. + Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer + X axis offset (or generic dimension 1), in the sensor's raw units + Y axis offset (or generic dimension 2), in the sensor's raw units + Z axis offset (or generic dimension 3), in the sensor's raw units + Generic dimension 4, in the sensor's raw units + Generic dimension 5, in the sensor's raw units + Generic dimension 6, in the sensor's raw units + + + Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. + 1: Trigger actuator ID assignment and direction mapping. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging) + Reserved + Empty + Empty + Empty + + + Request the reboot or shutdown of system components. + 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. + 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + + + Hold / continue the current action + MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan + MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position + MAV_FRAME coordinate frame of hold point + Desired yaw angle in degrees + Latitude / X position + Longitude / Y position + Altitude / Z position + + + start running a mission + first_item: the first mission item to run + last_item: the last mission item to run (after this item is run, the mission ends) + + + Arms / Disarms a component + 1 to arm, 0 to disarm + + + Request the home position from the vehicle. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Starts receiver pairing + 0:Spektrum + 0:Spektrum DSM2, 1:Spektrum DSMX + + + Request the interval between messages for a particular MAVLink message ID + The MAVLink message ID + + + Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM + The MAVLink message ID + The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate. + + + Request autopilot capabilities + 1: Request autopilot version + Reserved (all remaining params) + + + Start image capture sequence + Duration between two consecutive pictures (in seconds) + Number of images to capture total - 0 for unlimited capture + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop image capture sequence + Reserved + Reserved + + + + Enable or disable on-board camera triggering system. + Trigger enable/disable (0 for disable, 1 for start) + Shutter integration time (in ms) + Reserved + + + + Starts video capture + Camera ID (0 for all cameras), 1 for first, 2 for second, etc. + Frames per second + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop the current video capture + Reserved + Reserved + + + + Create a panorama at the current position + Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle) + Viewing angle vertical of panorama (in degrees) + Speed of the horizontal rotation (in degrees per second) + Speed of the vertical rotation (in degrees per second) + + + + Request VTOL transition + The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. + + + + + + + Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. + Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. + Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. + Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. + Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. + Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Altitude, in meters AMSL + + + Control the payload deployment. + Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + + + THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + No region of interest. + + + Point toward next MISSION. + + + Point toward given MISSION. + + + Point toward fixed location. + + + Point toward of given id. + + + + ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. + + Command / mission item is ok. + + + Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. + + + The system is refusing to accept this command from this source / communication partner. + + + Command or mission item is not supported, other commands would be accepted. + + + The coordinate frame of this command / mission item is not supported. + + + 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. + + + The X or latitude value is out of range. + + + The Y or longitude value is out of range. + + + The Z or altitude value is out of range. + + + + Specifies the datatype of a MAVLink parameter. + + 8-bit unsigned integer + + + 8-bit signed integer + + + 16-bit unsigned integer + + + 16-bit signed integer + + + 32-bit unsigned integer + + + 32-bit signed integer + + + 64-bit unsigned integer + + + 64-bit signed integer + + + 32-bit floating-point + + + 64-bit floating-point + + + + result from a mavlink command + + Command ACCEPTED and EXECUTED + + + Command TEMPORARY REJECTED/DENIED + + + Command PERMANENTLY DENIED + + + Command UNKNOWN/UNSUPPORTED + + + Command executed, but failed + + + + result in a mavlink mission ack + + mission accepted OK + + + generic error / not accepting mission commands at all right now + + + coordinate frame is not supported + + + command is not supported + + + mission item exceeds storage space + + + one of the parameters has an invalid value + + + param1 has an invalid value + + + param2 has an invalid value + + + param3 has an invalid value + + + param4 has an invalid value + + + x/param5 has an invalid value + + + y/param6 has an invalid value + + + param7 has an invalid value + + + received waypoint out of sequence + + + not accepting any mission commands from this communication partner + + + + Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. + + System is unusable. This is a "panic" condition. + + + Action should be taken immediately. Indicates error in non-critical systems. + + + Action must be taken immediately. Indicates failure in a primary system. + + + Indicates an error in secondary/redundant systems. + + + Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. + + + An unusual event has occured, though not an error condition. This should be investigated for the root cause. + + + Normal operational messages. Useful for logging. No action is required for these messages. + + + Useful non-operational messages that can assist in debugging. These should not occur during normal operation. + + + + Power supply status flags (bitmask) + + main brick power supply valid + + + main servo power supply valid for FMU + + + USB power is connected + + + peripheral supply is in over-current state + + + hi-power peripheral supply is in over-current state + + + Power status has changed since boot + + + + SERIAL_CONTROL device types + + First telemetry port + + + Second telemetry port + + + First GPS port + + + Second GPS port + + + system shell + + + + SERIAL_CONTROL flags (bitmask) + + Set if this is a reply + + + Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message + + + Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set + + + Block on writes to the serial port + + + Send multiple replies until port is drained + + + + Enumeration of distance sensor types + + Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units + + + Ultrasound rangefinder, e.g. MaxBotix units + + + Infrared rangefinder, e.g. Sharp units + + + + Enumeration of sensor orientation, according to its rotations + + Roll: 0, Pitch: 0, Yaw: 0 + + + Roll: 0, Pitch: 0, Yaw: 45 + + + Roll: 0, Pitch: 0, Yaw: 90 + + + Roll: 0, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 0, Yaw: 180 + + + Roll: 0, Pitch: 0, Yaw: 225 + + + Roll: 0, Pitch: 0, Yaw: 270 + + + Roll: 0, Pitch: 0, Yaw: 315 + + + Roll: 180, Pitch: 0, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 45 + + + Roll: 180, Pitch: 0, Yaw: 90 + + + Roll: 180, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 180, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 225 + + + Roll: 180, Pitch: 0, Yaw: 270 + + + Roll: 180, Pitch: 0, Yaw: 315 + + + Roll: 90, Pitch: 0, Yaw: 0 + + + Roll: 90, Pitch: 0, Yaw: 45 + + + Roll: 90, Pitch: 0, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 135 + + + Roll: 270, Pitch: 0, Yaw: 0 + + + Roll: 270, Pitch: 0, Yaw: 45 + + + Roll: 270, Pitch: 0, Yaw: 90 + + + Roll: 270, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 90, Yaw: 0 + + + Roll: 0, Pitch: 270, Yaw: 0 + + + Roll: 0, Pitch: 180, Yaw: 90 + + + Roll: 0, Pitch: 180, Yaw: 270 + + + Roll: 90, Pitch: 90, Yaw: 0 + + + Roll: 180, Pitch: 90, Yaw: 0 + + + Roll: 270, Pitch: 90, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 0 + + + Roll: 270, Pitch: 180, Yaw: 0 + + + Roll: 90, Pitch: 270, Yaw: 0 + + + Roll: 180, Pitch: 270, Yaw: 0 + + + Roll: 270, Pitch: 270, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 270 + + + Roll: 315, Pitch: 315, Yaw: 315 + + + + Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. + + Autopilot supports MISSION float message type. + + + Autopilot supports the new param float message type. + + + Autopilot supports MISSION_INT scaled integer message type. + + + Autopilot supports COMMAND_INT scaled integer message type. + + + Autopilot supports the new param union message type. + + + Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. + + + Autopilot supports commanding attitude offboard. + + + Autopilot supports commanding position and velocity targets in local NED frame. + + + Autopilot supports commanding position and velocity targets in global scaled integers. + + + Autopilot supports terrain protocol / data handling. + + + Autopilot supports direct actuator control. + + + Autopilot supports the flight termination command. + + + Autopilot supports onboard compass calibration. + + + + Enumeration of estimator types + + This is a naive estimator without any real covariance feedback. + + + Computer vision based estimate. Might be up to scale. + + + Visual-inertial estimate. + + + Plain GPS estimate. + + + Estimator integrating GPS and inertial sensing. + + + + Enumeration of battery types + + Not specified. + + + Lithium polymer battery + + + Lithium-iron-phosphate battery + + + Lithium-ION battery + + + Nickel metal hydride battery + + + + Enumeration of battery functions + + Battery function is unknown + + + Battery supports all flight systems + + + Battery for the propulsion system + + + Avionics battery + + + Payload battery + + + + Enumeration of VTOL states + + MAV is not configured as VTOL + + + VTOL is in transition from multicopter to fixed-wing + + + VTOL is in transition from fixed-wing to multicopter + + + VTOL is in multicopter state + + + VTOL is in fixed-wing state + + + + Enumeration of landed detector states + + MAV landed state is unknown + + + MAV is landed (on ground) + + + MAV is in air + + + + Enumeration of the ADSB altimeter types + + Altitude reported from a Baro source using QNH reference + + + Altitude reported from a GNSS source + + + + ADSB classification for the type of vehicle emitting the transponder signal + + + + + + + + + + + + + + + + + + + + + + + These flags indicate status such as data validity of each data source. Set = data valid + + + + + + + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + Timestamp of the component clock since boot time in milliseconds. + + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new base mode + The new autopilot-specific mode. This field can be ignored by an autopilot. + + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw, 0 if nonexistant) + Differential pressure 2 (raw, 0 if nonexistant) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (milliseconds since system boot) + Roll angle (rad, -pi..+pi) + Pitch angle (rad, -pi..+pi) + Yaw angle (rad, -pi..+pi) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion component 1, w (1 in null-rotation) + Quaternion component 2, x (0 in null-rotation) + Quaternion component 3, y (0 in null-rotation) + Quaternion component 4, z (0 in null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the resolution of float is not sufficient. + Timestamp (milliseconds since system boot) + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude, positive north), expressed as m/s * 100 + Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Timestamp (microseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint. + System ID + Component ID + Start index, 0 by default + End index, -1 by default (-1: send list to end). Else a valid index of the list + + + This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! + System ID + Component ID + Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + End index, equal or greater than start index. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Sequence + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + + + Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol + System ID + Component ID + Sequence + + + Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs. + System ID + Component ID + Number of mission items in the sequence + + + Delete all mission items at once. + System ID + Component ID + + + A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. + Sequence + + + Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + See MAV_MISSION_RESULT enum + + + As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + Initial parameter value + Scale, maps the RC range [-1, 1] to a parameter value + Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Attitude covariance + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters. + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current MISSION/target in degrees + Distance to active MISSION in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. + Timestamp (milliseconds since system boot) + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), above MSL + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s + Ground Y Speed (Longitude), expressed as m/s + Ground Z Speed (Altitude), expressed as m/s + Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + X Position + Y Position + Z Position + X Speed (m/s) + Y Speed (m/s) + Z Speed (m/s) + X Acceleration (m/s^2) + Y Acceleration (m/s^2) + Z Acceleration (m/s^2) + Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + + + The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested data stream + The requested message rate + 1 to start sending, 0 to stop sending. + + + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + The ID of the requested data stream + The message rate + 1 stream is enabled, 0 stream is stopped. + + + This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their + The system to be controlled. + X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. + System ID + Component ID + The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Send a command with up to seven parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + Parameter 5, as defined by MAV_CMD enum. + Parameter 6, as defined by MAV_CMD enum. + Parameter 7, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed. + Command ID, as defined by MAV_CMD enum. + See MAV_RESULT enum + + + Setpoint in roll, pitch, yaw and thrust from the operator + Timestamp in milliseconds since system boot + Desired roll rate in radians per second + Desired pitch rate in radians per second + Desired yaw rate in radians per second + Collective thrust, normalized to 0 .. 1 + Flight mode switch position, 0.. 255 + Override mode switch position, 0.. 255 + + + Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + System ID + Component ID + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + Roll + Pitch + Yaw + + + DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Sent from autopilot to simulation. Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -1 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + Aux 1, -1 .. 1 + Aux 2, -1 .. 1 + Aux 3, -1 .. 1 + Aux 4, -1 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + RC channel 9 value, in microseconds + RC channel 10 value, in microseconds + RC channel 11 value, in microseconds + RC channel 12 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels * 10 in x-sensor direction (dezi-pixels) + Flow in pixels * 10 in y-sensor direction (dezi-pixels) + Flow in meters in x-sensor direction, angular-speed compensated + Flow in meters in y-sensor direction, angular-speed compensated + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X speed + Global Y speed + Global Z speed + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis (rad / sec) + Angular speed around Y axis (rad / sec) + Angular speed around Z axis (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + + + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis in body frame (rad / sec) + Angular speed around Y axis in body frame (rad / sec) + Angular speed around Z axis in body frame (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure (airspeed) in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + + + + Status of simulation environment, if used + True attitude quaternion component 1, w (1 in null-rotation) + True attitude quaternion component 2, x (0 in null-rotation) + True attitude quaternion component 3, y (0 in null-rotation) + True attitude quaternion component 4, z (0 in null-rotation) + Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees + Longitude in degrees + Altitude in meters + Horizontal position standard deviation + Vertical position standard deviation + True velocity in m/s in NORTH direction in earth-fixed NED frame + True velocity in m/s in EAST direction in earth-fixed NED frame + True velocity in m/s in DOWN direction in earth-fixed NED frame + + + + Status generated by radio and injected into MAVLink stream. + Local signal strength + Remote signal strength + Remaining free buffer space in percent. + Background noise level + Remote background noise level + Receive errors + Count of error corrected packets + + + File transfer message + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Time synchronization message. + Time sync timestamp 1 + Time sync timestamp 2 + + + Camera-IMU triggering and synchronisation message. + Timestamp for the image frame in microseconds + Image frame sequence + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + GPS ground speed (m/s * 100). If unknown, set to: 65535 + GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + GPS velocity in cm/s in EAST direction in earth-fixed NED frame + GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Number of satellites visible. If unknown, set to 255 + + + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + Indicated airspeed, expressed as m/s * 100 + True airspeed, expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. + System ID + Component ID + First log id (0 for first available) + Last log id (0xffff for last available) + + + Reply to LOG_REQUEST_LIST + Log id + Total number of logs + High log number + UTC timestamp of log in seconds since 1970, or 0 if not available + Size of the log (may be approximate) in bytes + + + Request a chunk of a log + System ID + Component ID + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes + + + Reply to LOG_REQUEST_DATA + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes (zero for end of log) + log data + + + Erase all logs + System ID + Component ID + + + Stop log transfer and resume normal logging + System ID + Component ID + + + data for injecting into the onboard GPS (used for DGPS) + System ID + Component ID + data length + raw data (110 is enough for 12 satellites of RTCMv2) + + + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + Number of DGPS satellites + Age of DGPS info + + + Power supply status + 5V rail voltage in millivolts + servo rail voltage in millivolts + power supply status flags (see MAV_POWER_STATUS enum) + + + Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. + See SERIAL_CONTROL_DEV enum + See SERIAL_CONTROL_FLAG enum + Timeout for reply data in milliseconds + Baudrate of transfer. Zero means no change. + how many bytes in this transfer + serial data + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + Width of a matrix or image + Height of a matrix or image + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + sequence number (starting with 0 on every transmission) + image data bytes + + + Time since system boot + Minimum distance the sensor can measure in centimeters + Maximum distance the sensor can measure in centimeters + Current distance reading + Type from MAV_DISTANCE_SENSOR enum. + Onboard ID of the sensor + Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + Measurement covariance in centimeters, 0 for unknown / invalid readings + + + Request for terrain data and terrain status + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + + + Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + bit within the terrain request mask + Terrain data in meters AMSL + + + Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. + Latitude (degrees *10^7) + Longitude (degrees *10^7) + + + Response from a TERRAIN_CHECK request + Latitude (degrees *10^7) + Longitude (degrees *10^7) + grid spacing (zero if terrain at this location unavailable) + Terrain height in meters AMSL + Current vehicle height above lat/lon terrain height (meters) + Number of 4x4 terrain blocks waiting to be received or read from disk + Number of 4x4 terrain blocks in memory + + + Barometer readings for 2nd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + Motion capture attitude and position + Timestamp (micros since boot or Unix epoch) + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + X position in meters (NED) + Y position in meters (NED) + Z position in meters (NED) + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + System ID + Component ID + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + The current system altitude. + Timestamp (milliseconds since system boot) + This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + This is the altitude above the home position. It resets on each change of the current home position. + This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + + + The autopilot is requesting a resource (file, binary, other type of data) + Request ID. This ID should be re-used when sending back URI contents + The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + + + Barometer readings for 3rd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + current motion information from a designated system + Timestamp in milliseconds since system boot + bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + AMSL, in meters + target velocity (0,0,0) for unknown + linear target acceleration (0,0,0) for unknown + (1 0 0 0 for unknown) + (0 0 0 for unknown) + eph epv + button states or switches of a tracker device + + + The smoothed, monotonic system state used to feed the control loops of the system. + Timestamp (micros since boot or Unix epoch) + X acceleration in body frame + Y acceleration in body frame + Z acceleration in body frame + X velocity in body frame + Y velocity in body frame + Z velocity in body frame + X position in local frame + Y position in local frame + Z position in local frame + Airspeed, set to -1 if unknown + Variance of body velocity estimate + Variance in local position + The attitude, represented as Quaternion + Angular rate in roll axis + Angular rate in pitch axis + Angular rate in yaw axis + + + Battery information + Battery ID + Function of the battery + Type (chemistry) of the battery + Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + + + Version and capability of autopilot software + bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + Firmware version number + Middleware version number + Operating system version number + HW / board version (last 8 bytes should be silicon ID, if any) + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + ID of the board vendor + ID of the product + UID if provided by hardware + + + The location of a landing area captured from a downward facing camera + Timestamp (micros since boot or Unix epoch) + The ID of the target if multiple targets are present + MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + X-axis angular offset (in radians) of the target from the center of the image + Y-axis angular offset (in radians) of the target from the center of the image + Distance to the target from the vehicle in meters + Size in radians of target along x-axis + Size in radians of target along y-axis + + + + Vibration levels and accelerometer clipping + Timestamp (micros since boot or Unix epoch) + Vibration levels on X-axis + Vibration levels on Y-axis + Vibration levels on Z-axis + first accelerometer clipping count + second accelerometer clipping count + third accelerometer clipping count + + + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + System ID. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + This interface replaces DATA_STREAM + The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + + + Provides state for additional features + The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + + + The location and information of an ADSB vehicle + ICAO address + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Type from ADSB_ALTITUDE_TYPE enum + Altitude(ASL) in millimeters + Course over ground in centidegrees + The horizontal velocity in centimeters/second + The vertical velocity in centimeters/second, positive is up + The callsign, 8+null + Type from ADSB_EMITTER_TYPE enum + Time since last communication in seconds + Flags to indicate various statuses including valid data fields + Squawk code + + + Message implementing parts of the V2 payload specs in V1 frames for transitional support. + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Starting address of the debug variables + Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + Memory contents at specified address + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + Timestamp (milliseconds since system boot) + index of debug variable + DEBUG value + + + diff --git a/message_definitions/v1.0/matrixpilot.xml b/message_definitions/v1.0/matrixpilot.xml new file mode 100644 index 0000000..29d368d --- /dev/null +++ b/message_definitions/v1.0/matrixpilot.xml @@ -0,0 +1,284 @@ + + + common.xml + + + + + + + + Action required when performing CMD_PREFLIGHT_STORAGE + + Read all parameters from storage + + + Write all parameters to storage + + + Clear all parameters in storage + + + Read specific parameters from storage + + + Write specific parameters to storage + + + Clear specific parameters in storage + + + do nothing + + + + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED + Storage area as defined by parameter database + Storage flags as defined by parameter database + Empty + Empty + Empty + Empty + + + + + + + + + Depreciated but used as a compiler flag. Do not remove + System ID + Component ID + + + Reqest reading of flexifunction data + System ID + Component ID + Type of flexifunction data requested + index into data where needed + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + Total count of functions + Address in the flexifunction data, Set to 0xFFFF to use address in target memory + Size of the + Settings data + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + Settings data + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + Flexifunction command type + + + Acknowldge sucess or failure of a flexifunction command + Command acknowledged + result of acknowledge + + + Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A + Serial UDB Extra Time + Serial UDB Extra Status + Serial UDB Extra Latitude + Serial UDB Extra Longitude + Serial UDB Extra Altitude + Serial UDB Extra Waypoint Index + Serial UDB Extra Rmat 0 + Serial UDB Extra Rmat 1 + Serial UDB Extra Rmat 2 + Serial UDB Extra Rmat 3 + Serial UDB Extra Rmat 4 + Serial UDB Extra Rmat 5 + Serial UDB Extra Rmat 6 + Serial UDB Extra Rmat 7 + Serial UDB Extra Rmat 8 + Serial UDB Extra GPS Course Over Ground + Serial UDB Extra Speed Over Ground + Serial UDB Extra CPU Load + Serial UDB Extra Voltage in MilliVolts + Serial UDB Extra 3D IMU Air Speed + Serial UDB Extra Estimated Wind 0 + Serial UDB Extra Estimated Wind 1 + Serial UDB Extra Estimated Wind 2 + Serial UDB Extra Magnetic Field Earth 0 + Serial UDB Extra Magnetic Field Earth 1 + Serial UDB Extra Magnetic Field Earth 2 + Serial UDB Extra Number of Sattelites in View + Serial UDB Extra GPS Horizontal Dilution of Precision + + + Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B + Serial UDB Extra Time + Serial UDB Extra PWM Input Channel 1 + Serial UDB Extra PWM Input Channel 2 + Serial UDB Extra PWM Input Channel 3 + Serial UDB Extra PWM Input Channel 4 + Serial UDB Extra PWM Input Channel 5 + Serial UDB Extra PWM Input Channel 6 + Serial UDB Extra PWM Input Channel 7 + Serial UDB Extra PWM Input Channel 8 + Serial UDB Extra PWM Input Channel 9 + Serial UDB Extra PWM Input Channel 10 + Serial UDB Extra PWM Output Channel 1 + Serial UDB Extra PWM Output Channel 2 + Serial UDB Extra PWM Output Channel 3 + Serial UDB Extra PWM Output Channel 4 + Serial UDB Extra PWM Output Channel 5 + Serial UDB Extra PWM Output Channel 6 + Serial UDB Extra PWM Output Channel 7 + Serial UDB Extra PWM Output Channel 8 + Serial UDB Extra PWM Output Channel 9 + Serial UDB Extra PWM Output Channel 10 + Serial UDB Extra IMU Location X + Serial UDB Extra IMU Location Y + Serial UDB Extra IMU Location Z + Serial UDB Extra Status Flags + Serial UDB Extra Oscillator Failure Count + Serial UDB Extra IMU Velocity X + Serial UDB Extra IMU Velocity Y + Serial UDB Extra IMU Velocity Z + Serial UDB Extra Current Waypoint Goal X + Serial UDB Extra Current Waypoint Goal Y + Serial UDB Extra Current Waypoint Goal Z + Serial UDB Extra Stack Memory Free + + + Backwards compatible version of SERIAL_UDB_EXTRA F4: format + Serial UDB Extra Roll Stabilization with Ailerons Enabled + Serial UDB Extra Roll Stabilization with Rudder Enabled + Serial UDB Extra Pitch Stabilization Enabled + Serial UDB Extra Yaw Stabilization using Rudder Enabled + Serial UDB Extra Yaw Stabilization using Ailerons Enabled + Serial UDB Extra Navigation with Ailerons Enabled + Serial UDB Extra Navigation with Rudder Enabled + Serial UDB Extra Type of Alitude Hold when in Stabilized Mode + Serial UDB Extra Type of Alitude Hold when in Waypoint Mode + Serial UDB Extra Firmware racing mode enabled + + + Backwards compatible version of SERIAL_UDB_EXTRA F5: format + Serial UDB YAWKP_AILERON Gain for Proporional control of navigation + Serial UDB YAWKD_AILERON Gain for Rate control of navigation + Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization + YAW_STABILIZATION_AILERON Proportional control + Gain For Boosting Manual Aileron control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F6: format + Serial UDB Extra PITCHGAIN Proportional Control + Serial UDB Extra Pitch Rate Control + Serial UDB Extra Rudder to Elevator Mix + Serial UDB Extra Roll to Elevator Mix + Gain For Boosting Manual Elevator control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F7: format + Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation + Serial UDB YAWKD_RUDDER Gain for Rate control of navigation + Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization + SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized + Serial UDB Extra Return To Landing - Angle to Pitch Plane Down + + + Backwards compatible version of SERIAL_UDB_EXTRA F8: format + Serial UDB Extra HEIGHT_TARGET_MAX + Serial UDB Extra HEIGHT_TARGET_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MAX + Serial UDB Extra ALT_HOLD_PITCH_MIN + Serial UDB Extra ALT_HOLD_PITCH_MAX + Serial UDB Extra ALT_HOLD_PITCH_HIGH + + + Backwards compatible version of SERIAL_UDB_EXTRA F13: format + Serial UDB Extra GPS Week Number + Serial UDB Extra MP Origin Latitude + Serial UDB Extra MP Origin Longitude + Serial UDB Extra MP Origin Altitude Above Sea Level + + + Backwards compatible version of SERIAL_UDB_EXTRA F14: format + Serial UDB Extra Wind Estimation Enabled + Serial UDB Extra Type of GPS Unit + Serial UDB Extra Dead Reckoning Enabled + Serial UDB Extra Type of UDB Hardware + Serial UDB Extra Type of Airframe + Serial UDB Extra Reboot Regitster of DSPIC + Serial UDB Extra Last dspic Trap Flags + Serial UDB Extra Type Program Address of Last Trap + Serial UDB Extra Number of Ocillator Failures + Serial UDB Extra UDB Internal Clock Configuration + Serial UDB Extra Type of Flight Plan + + + Backwards compatible version of SERIAL_UDB_EXTRA F15 and F16: format + Serial UDB Extra Model Name Of Vehicle + Serial UDB Extra Registraton Number of Vehicle + + + Serial UDB Extra Name of Expected Lead Pilot + Serial UDB Extra URL of Lead Pilot or Team + + + The altitude measured by sensors and IMU + Timestamp (milliseconds since system boot) + GPS altitude in meters, expressed as * 1000 (millimeters), above MSL + IMU altitude above ground in meters, expressed as * 1000 (millimeters) + barometeric altitude above ground in meters, expressed as * 1000 (millimeters) + Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) + Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) + Extra altitude above ground in meters, expressed as * 1000 (millimeters) + + + The airspeed measured by sensors and IMU + Timestamp (milliseconds since system boot) + Airspeed estimate from IMU, cm/s + Pitot measured forward airpseed, cm/s + Hot wire anenometer measured airspeed, cm/s + Ultrasonic measured airspeed, cm/s + Angle of attack sensor, degrees * 10 + Yaw angle sensor, degrees * 10 + + + + diff --git a/message_definitions/v1.0/minimal.xml b/message_definitions/v1.0/minimal.xml new file mode 100644 index 0000000..88985a5 --- /dev/null +++ b/message_definitions/v1.0/minimal.xml @@ -0,0 +1,189 @@ + + + 2 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + PIXHAWK autopilot, http://pixhawk.ethz.ch + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version + + + diff --git a/message_definitions/v1.0/paparazzi.xml b/message_definitions/v1.0/paparazzi.xml new file mode 100755 index 0000000..2200075 --- /dev/null +++ b/message_definitions/v1.0/paparazzi.xml @@ -0,0 +1,38 @@ + + + common.xml + 3 + + + + + + Message encoding a mission script item. This message is emitted upon a request for the next script item. + System ID + Component ID + Sequence + The name of the mission script, NULL terminated. + + + Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. + System ID + Component ID + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. + System ID + Component ID + Number of script items in the sequence + + + This message informs about the currently active SCRIPT. + Active Sequence + + + diff --git a/message_definitions/v1.0/python_array_test.xml b/message_definitions/v1.0/python_array_test.xml new file mode 100644 index 0000000..f230d01 --- /dev/null +++ b/message_definitions/v1.0/python_array_test.xml @@ -0,0 +1,67 @@ + + + +common.xml + + + Array test #0. + Stub field + Value array + Value array + Value array + Value array + + + Array test #1. + Value array + + + Array test #3. + Stub field + Value array + + + Array test #4. + Value array + Stub field + + + Array test #5. + Value array + Value array + + + Array test #6. + Stub field + Stub field + Stub field + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #7. + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #8. + Stub field + Value array + Value array + + + diff --git a/message_definitions/v1.0/satball.xml b/message_definitions/v1.0/satball.xml new file mode 100644 index 0000000..3392f08 --- /dev/null +++ b/message_definitions/v1.0/satball.xml @@ -0,0 +1,24 @@ + + + common.xml + + + + + + + This message encodes all the motor RPM measurments form the actuator board + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + This vector contains imu_acc [ax ay az] + This vector contains imu_gyro [gx gy gz] + This vector contains imu_mag [mx my mz] + This vector contains all the rpm values for each motor [m1 m2 m3 m4] + + + This message encodes all the motor driver values for the motors in the tetrahedron configuration + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Can take the value between 0x00 to 0xFFFF [m1 m2 m3 m4] + Can take the value between 0x00 to 0xFFFF [magx magy magz] + + + diff --git a/message_definitions/v1.0/satball_old.xml b/message_definitions/v1.0/satball_old.xml new file mode 100644 index 0000000..463eb47 --- /dev/null +++ b/message_definitions/v1.0/satball_old.xml @@ -0,0 +1,26 @@ + + + common.xml + + + + + + + This message encodes all the motor RPM measurments form the actuator board + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + + + + + + + This message encodes all the motor driver values for the motors in the tetrahedron configuration + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Can take the value between 0x00 to 0xFF + Can take the value between 0x00 to 0xFF + Can take the value between 0x00 to 0xFF + Can take the value between 0x00 to 0xFF + + + diff --git a/message_definitions/v1.0/slugs.xml b/message_definitions/v1.0/slugs.xml new file mode 100755 index 0000000..a985eab --- /dev/null +++ b/message_definitions/v1.0/slugs.xml @@ -0,0 +1,339 @@ + + + common.xml + + + + + + Does nothing. + 1 to arm, 0 to disarm + + + + + + Return vehicle to base. + 0: return to base, 1: track mobile base + + + Stops the vehicle from returning to base and resumes flight. + + + Turns the vehicle's visible or infrared lights on or off. + 0: visible lights, 1: infrared lights + 0: turn on, 1: turn off + + + Requests vehicle to send current mid-level commands to ground station. + + + Requests storage of mid-level commands. + Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM + + + + + + Slugs-specific navigation modes. + + No change to SLUGS mode. + + + Vehicle is in liftoff mode. + + + Vehicle is in passthrough mode, being controlled by a pilot. + + + Vehicle is in waypoint mode, navigating to waypoints. + + + Vehicle is executing mid-level commands. + + + Vehicle is returning to the home location. + + + Vehicle is landing. + + + Lost connection with vehicle. + + + Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. + + + Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. + + + Vehicle is patrolling along lines between waypoints. + + + Vehicle is grounded or an error has occurred. + + + + + These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console + has control of the surface, and if not then the autopilot has control of the surface. + + 0b10000000 Throttle control passes through to pilot console. + + + 0b01000000 Left aileron control passes through to pilot console. + + + 0b00100000 Right aileron control passes through to pilot console. + + + 0b00010000 Rudder control passes through to pilot console. + + + 0b00001000 Left elevator control passes through to pilot console. + + + 0b00000100 Right elevator control passes through to pilot console. + + + 0b00000010 Left flap control passes through to pilot console. + + + 0b00000001 Right flap control passes through to pilot console. + + + + + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the nav filter in m/s + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + Commanded altitude in 0.1 m + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Clock Status. See table 47 page 211 OEMStar Manual + Visible satellites reported by Gps + Used satellites in Solution + GPS+GLONASS satellites in Solution + GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) + Percent used GPS + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground. + The system setting the commands + Commanded Altitude in meters + Commanded Airspeed in m/s + Commanded Turnrate in rad/s + + + + This message sets the control surfaces for selective passthrough mode. + The system setting the commands + Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. + + + + Orders generated to the SLUGS camera mount. + The system reporting the action + Order the mount to pan: -1 left, 0 No pan motion, +1 right + Order the mount to tilt: -1 down, 0 No tilt motion, +1 up + Order the zoom values 0 to 10 + Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored + + + + Control for surface; pending and order to origin. + The system setting the commands + ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder + Pending + Order to origin + + + + + + + Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled + The system reporting the action + Mobile Latitude + Mobile Longitude + + + + Control for camara. + The system setting the commands + ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight + 1: up/on 2: down/off 3: auto/reset/no action + + + + Transmits the position of watch + The system reporting the action + ISR Latitude + ISR Longitude + ISR Height + Option 1 + Option 2 + Option 3 + + + + + + + Transmits the readings from the voltage and current sensors + It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM + Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V + Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value + + + + Transmits the actual Pan, Tilt and Zoom values of the camera unit + The actual Zoom Value + The Pan value in 10ths of degree + The Tilt value in 10ths of degree + + + + Transmits the actual status values UAV in flight + The ID system reporting the action + Latitude UAV + Longitude UAV + Altitude UAV + Speed UAV + Course UAV + + + + This contains the status of the GPS readings + Number of times checksum has failed + The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a + Indicates if GN, GL or GP messages are being received + A = data valid, V = data invalid + Magnetic variation, degrees + Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course + Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid + + + + Transmits the diagnostics data from the Novatel OEMStar GPS + The Time Status. See Table 8 page 27 Novatel OEMStar Manual + Status Bitfield. See table 69 page 350 Novatel OEMstar Manual + solution Status. See table 44 page 197 + position type. See table 43 page 196 + velocity type. See table 43 page 196 + Age of the position solution in seconds + Times the CRC has failed since boot + + + + Diagnostic data Sensor MCU + Float field 1 + Float field 2 + Int 16 field 1 + Int 8 field 1 + + + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup. + The onboard software version + + + diff --git a/message_definitions/v1.0/test.xml b/message_definitions/v1.0/test.xml new file mode 100644 index 0000000..02bc032 --- /dev/null +++ b/message_definitions/v1.0/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/message_definitions/v1.0/ualberta.xml b/message_definitions/v1.0/ualberta.xml new file mode 100644 index 0000000..bb57e84 --- /dev/null +++ b/message_definitions/v1.0/ualberta.xml @@ -0,0 +1,76 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + + Raw input pulse widts sent to output + + + Inputs are normalized using calibration, the converted back to raw pulse widths for output + + + dfsdfs + + + dfsfds + + + dfsdfsdfs + + + + Navigation filter mode + + + AHRS mode + + + INS/GPS initialization mode + + + INS/GPS mode + + + + Mode currently commanded by pilot + + sdf + + + dfs + + + Rotomotion mode + + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/missionlib/mavlink_missionlib_data.h b/missionlib/mavlink_missionlib_data.h new file mode 100644 index 0000000..c825fbc --- /dev/null +++ b/missionlib/mavlink_missionlib_data.h @@ -0,0 +1,58 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + 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 . + + ****************************************************************************/ + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ + +// Disable auto-data structures +#ifndef MAVLINK_NO_DATA +#define MAVLINK_NO_DATA +#endif + +#include "mavlink.h" +#include + +/* MISSION LIB DATA STORAGE */ + +enum MAVLINK_PM_PARAMETERS +{ + MAVLINK_PM_PARAM_SYSTEM_ID, + MAVLINK_PM_PARAM_ATT_K_D, + MAVLINK_PM_MAX_PARAM_COUNT // VERY IMPORTANT! KEEP THIS AS LAST ENTRY +}; + + +/* DO NOT EDIT THIS FILE BELOW THIS POINT! */ + +#ifndef MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 +#endif + + +//extern void mavlink_pm_queued_send(); +struct mavlink_pm_storage { + char param_names[MAVLINK_PM_MAX_PARAM_COUNT][MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN]; ///< Parameter names + float param_values[MAVLINK_PM_MAX_PARAM_COUNT]; ///< Parameter values + uint16_t next_param; + uint16_t size; +}; + +typedef struct mavlink_pm_storage mavlink_pm_storage; + +void mavlink_pm_reset_params(mavlink_pm_storage* pm); diff --git a/missionlib/mavlink_parameters.c b/missionlib/mavlink_parameters.c new file mode 100644 index 0000000..18a05b3 --- /dev/null +++ b/missionlib/mavlink_parameters.c @@ -0,0 +1,150 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + 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 . + + ****************************************************************************/ + +#include "mavlink_missionlib_data.h" +#include "mavlink_parameters.h" +#include "math.h" /* isinf / isnan checks */ + +extern mavlink_system_t mavlink_system; +extern mavlink_pm_storage pm; + +extern void mavlink_missionlib_send_message(mavlink_message_t* msg); +extern void mavlink_missionlib_send_gcs_string(const char* string); + +void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t* msg) +{ + switch (msg->msgid) + { + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: + { + // Start sending parameters + pm.next_param = 0; + mavlink_missionlib_send_gcs_string("PM SENDING LIST"); + } + break; + case MAVLINK_MSG_ID_PARAM_SET: + { + mavlink_param_set_t set; + mavlink_msg_param_set_decode(msg, &set); + + // Check if this message is for this system + if (set.target_system == mavlink_system.sysid && set.target_component == mavlink_system.compid) + { + char* key = set.param_id; + + for (uint16_t i = 0; i < MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN; i++) + { + bool match = true; + for (uint16_t j = 0; j < MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN; j++) + { + // Compare + if (pm.param_names[i][j] != key[j]) + { + match = false; + } + + // End matching if null termination is reached + if (pm.param_names[i][j] == '\0') + { + break; + } + } + + // Check if matched + if (match) + { + // Only write and emit changes if there is actually a difference + // AND only write if new value is NOT "not-a-number" + // AND is NOT infinity + if (pm.param_values[i] != set.param_value + && !isnan(set.param_value) + && !isinf(set.param_value)) + { + pm.param_values[i] = set.param_value; + // Report back new value +#ifndef MAVLINK_USE_CONVENIENCE_FUNCTIONS + mavlink_message_t tx_msg; + mavlink_msg_param_value_pack_chan(mavlink_system.sysid, + mavlink_system.compid, + MAVLINK_COMM_0, + &tx_msg, + pm.param_names[i], + pm.param_values[i], + MAVLINK_TYPE_FLOAT, + pm.size, + i); + mavlink_missionlib_send_message(&tx_msg); +#else + mavlink_msg_param_value_send(MAVLINK_COMM_0, + pm.param_names[i], + pm.param_values[i], + MAVLINK_TYPE_FLOAT, + pm.size, + i); +#endif + + mavlink_missionlib_send_gcs_string("PM received param"); + } // End valid value check + } // End match check + } // End for loop + } // End system ID check + + } // End case + break; + + } // End switch + +} + + /** + * @brief Send low-priority messages at a maximum rate of xx Hertz + * + * This function sends messages at a lower rate to not exceed the wireless + * bandwidth. It sends one message each time it is called until the buffer is empty. + * Call this function with xx Hertz to increase/decrease the bandwidth. + */ + void mavlink_pm_queued_send(void) + { + //send parameters one by one + if (pm.next_param < pm.size) + { + //for (int i.. all active comm links) +#ifndef MAVLINK_USE_CONVENIENCE_FUNCTIONS + mavlink_message_t tx_msg; + mavlink_msg_param_value_pack_chan(mavlink_system.sysid, + mavlink_system.compid, + MAVLINK_COMM_0, + &tx_msg, + pm.param_names[pm.next_param], + pm.param_values[pm.next_param], + MAVLINK_TYPE_FLOAT, + pm.size, + pm.next_param); + mavlink_missionlib_send_message(&tx_msg); +#else + mavlink_msg_param_value_send(MAVLINK_COMM_0, + pm.param_names[pm.next_param], + pm.param_values[pm.next_param], + MAV_DATA_TYPE_FLOAT, + pm.size, + pm.next_param); +#endif + pm.next_param++; + } + } diff --git a/missionlib/mavlink_parameters.h b/missionlib/mavlink_parameters.h new file mode 100644 index 0000000..0d7841f --- /dev/null +++ b/missionlib/mavlink_parameters.h @@ -0,0 +1,38 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + 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 . + + ****************************************************************************/ + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ + +// Disable auto-data structures +#ifndef MAVLINK_NO_DATA +#define MAVLINK_NO_DATA +#endif + +#include "mavlink.h" +#include + +/* PARAMETER MANAGER - MISSION LIB */ + +#ifndef MAVLINK_PM_TEXT_FEEDBACK +#define MAVLINK_PM_TEXT_FEEDBACK 1 ///< Report back status information as text +#endif + +void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t* msg); +void mavlink_pm_queued_send(void); \ No newline at end of file diff --git a/missionlib/testing/Makefile b/missionlib/testing/Makefile new file mode 100644 index 0000000..134aa47 --- /dev/null +++ b/missionlib/testing/Makefile @@ -0,0 +1,12 @@ +VERSION = 1.00 +CC = gcc +CFLAGS = -I ../../include/common -Wall -Werror -DVERSION=\"$(MAVLINK_VERSION)\" -std=c99 +LDFLAGS = "" + +OBJ = udp.o + +udptest: $(OBJ) + $(CC) $(CFLAGS) -o udptest $(OBJ) $(LDFLAGS) + +%.o: %.c + $(CC) $(CFLAGS) -c $< \ No newline at end of file diff --git a/missionlib/testing/main.c b/missionlib/testing/main.c new file mode 100644 index 0000000..21aa1f7 --- /dev/null +++ b/missionlib/testing/main.c @@ -0,0 +1,373 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + and Bryan Godbolt godbolt ( a t ) ualberta.ca + + adapted from example written by 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 . + + ****************************************************************************/ +/* + 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 sucessfully on Ubuntu 10.04 with the following command + + gcc -I ../../pixhawk/mavlink/include -o udp-server udp.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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if (defined __QNX__) | (defined __QNXNTO__) +/* QNX specific headers */ +#include +#else +/* Linux / MacOS POSIX timer headers */ +#include +#include +#include +#endif + +/* FIRST: MAVLink setup */ +//#define MAVLINK_CONFIGURED +//#define MAVLINK_NO_DATA +//#define MAVLINK_WPM_VERBOSE + +/* 0: Include MAVLink types */ +#include "mavlink_types.h" + +/* 1: Define mavlink system storage */ +mavlink_system_t mavlink_system; + +/* 2: Include actual protocol, REQUIRES mavlink_system */ +#include "mavlink.h" + +/* 3: Define waypoint helper functions */ +void mavlink_wpm_send_message(mavlink_message_t* msg); +void mavlink_wpm_send_gcs_string(const char* string); +uint64_t mavlink_wpm_get_system_timestamp(); +void mavlink_missionlib_send_message(mavlink_message_t* msg); +void mavlink_missionlib_send_gcs_string(const char* string); +uint64_t mavlink_missionlib_get_system_timestamp(); + +/* 4: Include waypoint protocol */ +#include "waypoints.h" +mavlink_wpm_storage wpm; + + +#include "mavlink_missionlib_data.h" +#include "mavlink_parameters.h" + +mavlink_pm_storage pm; + +/** + * @brief reset all parameters to default + * @warning DO NOT USE THIS IN FLIGHT! + */ +void mavlink_pm_reset_params(mavlink_pm_storage* pm) +{ + pm->size = MAVLINK_PM_MAX_PARAM_COUNT; + // 1) MAVLINK_PM_PARAM_SYSTEM_ID + pm->param_values[MAVLINK_PM_PARAM_SYSTEM_ID] = 12; + strcpy(pm->param_names[MAVLINK_PM_PARAM_SYSTEM_ID], "SYS_ID"); + // 2) MAVLINK_PM_PARAM_ATT_K_D + pm->param_values[MAVLINK_PM_PARAM_ATT_K_D] = 0.3f; + strcpy(pm->param_names[MAVLINK_PM_PARAM_ATT_K_D], "ATT_K_D"); +} + + +#define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why) + +char help[] = "--help"; + + +char target_ip[100]; + +float position[6] = {}; +int sock; +struct sockaddr_in gcAddr; +struct sockaddr_in locAddr; +uint8_t buf[BUFFER_LENGTH]; +ssize_t recsize; +socklen_t fromlen; +int bytes_sent; +mavlink_message_t msg; +uint16_t len; +int i = 0; +unsigned int temp = 0; + +uint64_t microsSinceEpoch(); + + + + +/* Provide the interface functions for the waypoint manager */ + +/* + * @brief Sends a MAVLink message over UDP + */ + +void mavlink_missionlib_send_message(mavlink_message_t* msg) +{ + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; + uint16_t len = mavlink_msg_to_send_buffer(buf, msg); + uint16_t bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in)); + + printf("SENT %d bytes\n", bytes_sent); +} + +void mavlink_missionlib_send_gcs_string(const char* string) +{ + const int len = 50; + mavlink_statustext_t status; + int i = 0; + while (i < len - 1) + { + status.text[i] = string[i]; + if (string[i] == '\0') + break; + i++; + } + status.text[i] = '\0'; // Enforce null termination + mavlink_message_t msg; + + mavlink_msg_statustext_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &status); + mavlink_missionlib_send_message(&msg); +} + +uint64_t mavlink_missionlib_get_system_timestamp() +{ + struct timeval tv; + gettimeofday(&tv, NULL); + return ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec; +} + +float roll, pitch, yaw; +uint32_t latitude, longitude, altitude; +uint16_t speedx, speedy, speedz; +float rollspeed, pitchspeed, yawspeed; +bool hilEnabled = false; + +int main(int argc, char* argv[]) +{ + // Initialize MAVLink + mavlink_wpm_init(&wpm); + mavlink_system.sysid = 5; + mavlink_system.compid = 20; + mavlink_pm_reset_params(&pm); + + int32_t ground_distance; + uint32_t time_ms; + + + + // Create socket + sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); + + // 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(" \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 (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0) + { + 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); + + + printf("MAVLINK MISSION LIBRARY EXAMPLE PROCESS INITIALIZATION DONE, RUNNING..\n"); + + + for (;;) + { + bytes_sent = 0; + + /* Send Heartbeat */ + mavlink_msg_heartbeat_pack(mavlink_system.sysid, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, 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 Status */ + mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE, 500, 7500, 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(mavlink_system.sysid, 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 global position */ + if (hilEnabled) + { + mavlink_msg_global_position_int_pack(mavlink_system.sysid, 200, &msg, time_ms, latitude, longitude, altitude, ground_distance, speedx, speedy, speedz, (yaw/M_PI)*180*100); + 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(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), roll, pitch, yaw, rollspeed, pitchspeed, yawspeed); + len = mavlink_msg_to_send_buffer(buf, &msg); + bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in)); + + /* Send HIL outputs */ + float roll_ailerons = 0; // -1 .. 1 + float pitch_elevator = 0.2; // -1 .. 1 + float yaw_rudder = 0.1; // -1 .. 1 + float throttle = 0.9; // 0 .. 1 + mavlink_msg_hil_controls_pack_chan(mavlink_system.sysid, mavlink_system.compid, MAVLINK_COMM_0, &msg, microsSinceEpoch(), roll_ailerons, pitch_elevator, yaw_rudder, throttle, mavlink_system.mode, mavlink_system.nav_mode, 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)); + + 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); + + // Handle packet with waypoint component + mavlink_wpm_message_handler(&msg); + + // Handle packet with parameter component + mavlink_pm_message_handler(MAVLINK_COMM_0, &msg); + + // Print HIL values sent to system + if (msg.msgid == MAVLINK_MSG_ID_HIL_STATE) + { + mavlink_hil_state_t hil; + mavlink_msg_hil_state_decode(&msg, &hil); + printf("Received HIL state:\n"); + printf("R: %f P: %f Y: %f\n", hil.roll, hil.pitch, hil.yaw); + roll = hil.roll; + pitch = hil.pitch; + yaw = hil.yaw; + rollspeed = hil.rollspeed; + pitchspeed = hil.pitchspeed; + yawspeed = hil.yawspeed; + speedx = hil.vx; + speedy = hil.vy; + speedz = hil.vz; + latitude = hil.lat; + longitude = hil.lon; + altitude = hil.alt; + hilEnabled = true; + } + } + } + printf("\n"); + } + memset(buf, 0, BUFFER_LENGTH); + usleep(10000); // Sleep 10 ms + + + // Send one parameter + mavlink_pm_queued_send(); + } +} + + +/* 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 * 100000 + 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 \ No newline at end of file diff --git a/missionlib/testing/mavlink_missionlib_data.h b/missionlib/testing/mavlink_missionlib_data.h new file mode 100644 index 0000000..a040941 --- /dev/null +++ b/missionlib/testing/mavlink_missionlib_data.h @@ -0,0 +1,54 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + 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 . + + ****************************************************************************/ + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ + +// Disable auto-data structures +#ifndef MAVLINK_NO_DATA +#define MAVLINK_NO_DATA +#endif + +#include "mavlink.h" +#include + +/* MISSION LIB DATA STORAGE */ + +enum MAVLINK_PM_PARAMETERS +{ + MAVLINK_PM_PARAM_SYSTEM_ID, + MAVLINK_PM_PARAM_ATT_K_D, + MAVLINK_PM_MAX_PARAM_COUNT // VERY IMPORTANT! KEEP THIS AS LAST ENTRY +}; + + +/* DO NOT EDIT THIS FILE BELOW THIS POINT! */ + + +//extern void mavlink_pm_queued_send(); +struct mavlink_pm_storage { + char param_names[MAVLINK_PM_MAX_PARAM_COUNT][MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN]; ///< Parameter names + float param_values[MAVLINK_PM_MAX_PARAM_COUNT]; ///< Parameter values + uint16_t next_param; + uint16_t size; +}; + +typedef struct mavlink_pm_storage mavlink_pm_storage; + +void mavlink_pm_reset_params(mavlink_pm_storage* pm); \ No newline at end of file diff --git a/missionlib/testing/udptest.xcodeproj/project.pbxproj b/missionlib/testing/udptest.xcodeproj/project.pbxproj new file mode 100644 index 0000000..7bc7657 --- /dev/null +++ b/missionlib/testing/udptest.xcodeproj/project.pbxproj @@ -0,0 +1,222 @@ +// !$*UTF8*$! +{ + archiveVersion = 1; + classes = { + }; + objectVersion = 45; + objects = { + +/* Begin PBXBuildFile section */ + 348868D013F512010005F759 /* mavlink_parameters.c in Sources */ = {isa = PBXBuildFile; fileRef = 348868CF13F512010005F759 /* mavlink_parameters.c */; }; + 34E8AFDB13F5064C001100AA /* waypoints.c in Sources */ = {isa = PBXBuildFile; fileRef = 34E8AFDA13F5064C001100AA /* waypoints.c */; }; + 8DD76FAC0486AB0100D96B5E /* main.c in Sources */ = {isa = PBXBuildFile; fileRef = 08FB7796FE84155DC02AAC07 /* main.c */; settings = {ATTRIBUTES = (); }; }; +/* End PBXBuildFile section */ + +/* Begin PBXCopyFilesBuildPhase section */ + 8DD76FAF0486AB0100D96B5E /* CopyFiles */ = { + isa = PBXCopyFilesBuildPhase; + buildActionMask = 8; + dstPath = /usr/share/man/man1/; + dstSubfolderSpec = 0; + files = ( + ); + runOnlyForDeploymentPostprocessing = 1; + }; +/* End PBXCopyFilesBuildPhase section */ + +/* Begin PBXFileReference section */ + 08FB7796FE84155DC02AAC07 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 348868CF13F512010005F759 /* mavlink_parameters.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = mavlink_parameters.c; path = ../mavlink_parameters.c; sourceTree = SOURCE_ROOT; }; + 348868D113F512080005F759 /* mavlink_parameters.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = mavlink_parameters.h; path = ../mavlink_parameters.h; sourceTree = SOURCE_ROOT; }; + 34E8AFDA13F5064C001100AA /* waypoints.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = waypoints.c; path = ../waypoints.c; sourceTree = SOURCE_ROOT; }; + 34E8AFDC13F50659001100AA /* waypoints.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = waypoints.h; path = ../waypoints.h; sourceTree = SOURCE_ROOT; }; + 8DD76FB20486AB0100D96B5E /* udptest */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = udptest; sourceTree = BUILT_PRODUCTS_DIR; }; +/* End PBXFileReference section */ + +/* Begin PBXFrameworksBuildPhase section */ + 8DD76FAD0486AB0100D96B5E /* Frameworks */ = { + isa = PBXFrameworksBuildPhase; + buildActionMask = 2147483647; + files = ( + ); + runOnlyForDeploymentPostprocessing = 0; + }; +/* End PBXFrameworksBuildPhase section */ + +/* Begin PBXGroup section */ + 08FB7794FE84155DC02AAC07 /* udptest */ = { + isa = PBXGroup; + children = ( + 34E8AFDC13F50659001100AA /* waypoints.h */, + 08FB7795FE84155DC02AAC07 /* Source */, + C6A0FF2B0290797F04C91782 /* Documentation */, + 1AB674ADFE9D54B511CA2CBB /* Products */, + ); + name = udptest; + sourceTree = ""; + }; + 08FB7795FE84155DC02AAC07 /* Source */ = { + isa = PBXGroup; + children = ( + 348868D113F512080005F759 /* mavlink_parameters.h */, + 348868CF13F512010005F759 /* mavlink_parameters.c */, + 34E8AFDA13F5064C001100AA /* waypoints.c */, + 08FB7796FE84155DC02AAC07 /* main.c */, + ); + name = Source; + sourceTree = ""; + }; + 1AB674ADFE9D54B511CA2CBB /* Products */ = { + isa = PBXGroup; + children = ( + 8DD76FB20486AB0100D96B5E /* udptest */, + ); + name = Products; + sourceTree = ""; + }; + C6A0FF2B0290797F04C91782 /* Documentation */ = { + isa = PBXGroup; + children = ( + ); + name = Documentation; + sourceTree = ""; + }; +/* End PBXGroup section */ + +/* Begin PBXNativeTarget section */ + 8DD76FA90486AB0100D96B5E /* udptest */ = { + isa = PBXNativeTarget; + buildConfigurationList = 1DEB928508733DD80010E9CD /* Build configuration list for PBXNativeTarget "udptest" */; + buildPhases = ( + 8DD76FAB0486AB0100D96B5E /* Sources */, + 8DD76FAD0486AB0100D96B5E /* Frameworks */, + 8DD76FAF0486AB0100D96B5E /* CopyFiles */, + ); + buildRules = ( + ); + dependencies = ( + ); + name = udptest; + productInstallPath = "$(HOME)/bin"; + productName = udptest; + productReference = 8DD76FB20486AB0100D96B5E /* udptest */; + productType = "com.apple.product-type.tool"; + }; +/* End PBXNativeTarget section */ + +/* Begin PBXProject section */ + 08FB7793FE84155DC02AAC07 /* Project object */ = { + isa = PBXProject; + buildConfigurationList = 1DEB928908733DD80010E9CD /* Build configuration list for PBXProject "udptest" */; + compatibilityVersion = "Xcode 3.1"; + developmentRegion = English; + hasScannedForEncodings = 1; + knownRegions = ( + English, + Japanese, + French, + German, + ); + mainGroup = 08FB7794FE84155DC02AAC07 /* udptest */; + projectDirPath = ""; + projectRoot = ""; + targets = ( + 8DD76FA90486AB0100D96B5E /* udptest */, + ); + }; +/* End PBXProject section */ + +/* Begin PBXSourcesBuildPhase section */ + 8DD76FAB0486AB0100D96B5E /* Sources */ = { + isa = PBXSourcesBuildPhase; + buildActionMask = 2147483647; + files = ( + 8DD76FAC0486AB0100D96B5E /* main.c in Sources */, + 34E8AFDB13F5064C001100AA /* waypoints.c in Sources */, + 348868D013F512010005F759 /* mavlink_parameters.c in Sources */, + ); + runOnlyForDeploymentPostprocessing = 0; + }; +/* End PBXSourcesBuildPhase section */ + +/* Begin XCBuildConfiguration section */ + 1DEB928608733DD80010E9CD /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + ALWAYS_SEARCH_USER_PATHS = NO; + COPY_PHASE_STRIP = NO; + GCC_DYNAMIC_NO_PIC = NO; + GCC_ENABLE_FIX_AND_CONTINUE = YES; + GCC_MODEL_TUNING = G5; + GCC_OPTIMIZATION_LEVEL = 0; + INSTALL_PATH = /usr/local/bin; + PRODUCT_NAME = udptest; + }; + name = Debug; + }; + 1DEB928708733DD80010E9CD /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + ALWAYS_SEARCH_USER_PATHS = NO; + DEBUG_INFORMATION_FORMAT = "dwarf-with-dsym"; + GCC_MODEL_TUNING = G5; + INSTALL_PATH = /usr/local/bin; + PRODUCT_NAME = udptest; + }; + name = Release; + }; + 1DEB928A08733DD80010E9CD /* Debug */ = { + isa = XCBuildConfiguration; + buildSettings = { + ARCHS = "$(ARCHS_STANDARD_32_64_BIT)"; + GCC_C_LANGUAGE_STANDARD = gnu99; + GCC_OPTIMIZATION_LEVEL = 0; + GCC_WARN_ABOUT_RETURN_TYPE = YES; + GCC_WARN_UNUSED_VARIABLE = YES; + HEADER_SEARCH_PATHS = ( + ../../include/, + ../../include/common/, + ); + ONLY_ACTIVE_ARCH = YES; + PREBINDING = NO; + SDKROOT = macosx10.6; + }; + name = Debug; + }; + 1DEB928B08733DD80010E9CD /* Release */ = { + isa = XCBuildConfiguration; + buildSettings = { + ARCHS = "$(ARCHS_STANDARD_32_64_BIT)"; + GCC_C_LANGUAGE_STANDARD = gnu99; + GCC_WARN_ABOUT_RETURN_TYPE = YES; + GCC_WARN_UNUSED_VARIABLE = YES; + PREBINDING = NO; + SDKROOT = macosx10.6; + }; + name = Release; + }; +/* End XCBuildConfiguration section */ + +/* Begin XCConfigurationList section */ + 1DEB928508733DD80010E9CD /* Build configuration list for PBXNativeTarget "udptest" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + 1DEB928608733DD80010E9CD /* Debug */, + 1DEB928708733DD80010E9CD /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; + 1DEB928908733DD80010E9CD /* Build configuration list for PBXProject "udptest" */ = { + isa = XCConfigurationList; + buildConfigurations = ( + 1DEB928A08733DD80010E9CD /* Debug */, + 1DEB928B08733DD80010E9CD /* Release */, + ); + defaultConfigurationIsVisible = 0; + defaultConfigurationName = Release; + }; +/* End XCConfigurationList section */ + }; + rootObject = 08FB7793FE84155DC02AAC07 /* Project object */; +} diff --git a/missionlib/waypoints.c b/missionlib/waypoints.c new file mode 100644 index 0000000..44bddb6 --- /dev/null +++ b/missionlib/waypoints.c @@ -0,0 +1,1028 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + 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 . + + ****************************************************************************/ + +#include "waypoints.h" +#include + +bool debug = true; +bool verbose = true; + +extern mavlink_wpm_storage wpm; + +extern void mavlink_missionlib_send_message(mavlink_message_t* msg); +extern void mavlink_missionlib_send_gcs_string(const char* string); +extern uint64_t mavlink_missionlib_get_system_timestamp(); +extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, + float param2, float param3, float param4, float param5_lat_x, + float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command); + + +#define MAVLINK_WPM_NO_PRINTF + +uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER; + +void mavlink_wpm_init(mavlink_wpm_storage* state) +{ + // Set all waypoints to zero + + // Set count to zero + state->size = 0; + state->max_size = MAVLINK_WPM_MAX_WP_COUNT; + state->current_state = MAVLINK_WPM_STATE_IDLE; + state->current_partner_sysid = 0; + state->current_partner_compid = 0; + state->timestamp_lastaction = 0; + state->timestamp_last_send_setpoint = 0; + state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; + state->delay_setpoint = MAVLINK_WPM_SETPOINT_DELAY_DEFAULT; + state->idle = false; ///< indicates if the system is following the waypoints or is waiting + state->current_active_wp_id = -1; ///< id of current waypoint + state->yaw_reached = false; ///< boolean for yaw attitude reached + state->pos_reached = false; ///< boolean for position reached + state->timestamp_lastoutside_orbit = 0;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value + state->timestamp_firstinside_orbit = 0;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value + +} + +/* + * @brief Sends an waypoint ack message + */ +void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type) +{ + mavlink_message_t msg; + mavlink_mission_ack_t wpa; + + wpa.target_system = wpm.current_partner_sysid; + wpa.target_component = wpm.current_partner_compid; + wpa.type = type; + + mavlink_msg_mission_ack_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpa); + mavlink_missionlib_send_message(&msg); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + + if (MAVLINK_WPM_TEXT_FEEDBACK) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("Sent waypoint ACK"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system); +#endif + mavlink_missionlib_send_gcs_string("Sent waypoint ACK"); + } +} + +/* + * @brief Broadcasts the new target waypoint and directs the MAV to fly there + * + * This function broadcasts its new active waypoint sequence number and + * sends a message to the controller, advising it to fly to the coordinates + * of the waypoint with a given orientation + * + * @param seq The waypoint sequence number the MAV should fly to. + */ +void mavlink_wpm_send_waypoint_current(uint16_t seq) +{ + if(seq < wpm.size) + { + mavlink_mission_item_t *cur = &(wpm.waypoints[seq]); + + mavlink_message_t msg; + mavlink_mission_current_t wpc; + + wpc.seq = cur->seq; + + mavlink_msg_mission_current_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc); + mavlink_missionlib_send_message(&msg); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Set current waypoint\n"); //// printf("Broadcasted new current waypoint %u\n", wpc.seq); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds\n"); + } +} + +/* + * @brief Directs the MAV to fly to a position + * + * Sends a message to the controller, advising it to fly to the coordinates + * of the waypoint with a given orientation + * + * @param seq The waypoint sequence number the MAV should fly to. + */ +void mavlink_wpm_send_setpoint(uint16_t seq) +{ + if(seq < wpm.size) + { + mavlink_mission_item_t *cur = &(wpm.waypoints[seq]); + mavlink_missionlib_current_waypoint_changed(cur->seq, cur->param1, + cur->param2, cur->param3, cur->param4, cur->x, + cur->y, cur->z, cur->frame, cur->command); + + wpm.timestamp_last_send_setpoint = mavlink_missionlib_get_system_timestamp(); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n"); //// if (verbose) // printf("ERROR: index out of bounds\n"); + } +} + +void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count) +{ + mavlink_message_t msg; + mavlink_mission_count_t wpc; + + wpc.target_system = wpm.current_partner_sysid; + wpc.target_component = wpm.current_partner_compid; + wpc.count = count; + + mavlink_msg_mission_count_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc); + mavlink_missionlib_send_message(&msg); + + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint count"); //// if (verbose) // printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); +} + +void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq) +{ + if (seq < wpm.size) + { + mavlink_message_t msg; + mavlink_mission_item_t *wp = &(wpm.waypoints[seq]); + wp->target_system = wpm.current_partner_sysid; + wp->target_component = wpm.current_partner_compid; + mavlink_msg_mission_item_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, wp); + mavlink_missionlib_send_message(&msg); + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint"); //// if (verbose) // printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n"); + } +} + +void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq) +{ + if (seq < wpm.max_size) + { + mavlink_message_t msg; + mavlink_mission_request_t wpr; + wpr.target_system = wpm.current_partner_sysid; + wpr.target_component = wpm.current_partner_compid; + wpr.seq = seq; + mavlink_msg_mission_request_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpr); + mavlink_missionlib_send_message(&msg); + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint request"); //// if (verbose) // printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); + } + else + { + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity\n"); + } +} + +/* + * @brief emits a message that a waypoint reached + * + * This function broadcasts a message that a waypoint is reached. + * + * @param seq The waypoint sequence number the MAV has reached. + */ +void mavlink_wpm_send_waypoint_reached(uint16_t seq) +{ + mavlink_message_t msg; + mavlink_mission_item_reached_t wp_reached; + + wp_reached.seq = seq; + + mavlink_msg_mission_item_reached_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wp_reached); + mavlink_missionlib_send_message(&msg); + + if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint reached message"); //// if (verbose) // printf("Sent waypoint %u reached message\n", wp_reached.seq); + + // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); +} + +//float mavlink_wpm_distance_to_segment(uint16_t seq, float x, float y, float z) +//{ +// if (seq < wpm.size) +// { +// mavlink_mission_item_t *cur = waypoints->at(seq); +// +// const PxVector3 A(cur->x, cur->y, cur->z); +// const PxVector3 C(x, y, z); +// +// // seq not the second last waypoint +// if ((uint16_t)(seq+1) < wpm.size) +// { +// mavlink_mission_item_t *next = waypoints->at(seq+1); +// const PxVector3 B(next->x, next->y, next->z); +// const float r = (B-A).dot(C-A) / (B-A).lengthSquared(); +// if (r >= 0 && r <= 1) +// { +// const PxVector3 P(A + r*(B-A)); +// return (P-C).length(); +// } +// else if (r < 0.f) +// { +// return (C-A).length(); +// } +// else +// { +// return (C-B).length(); +// } +// } +// else +// { +// return (C-A).length(); +// } +// } +// else +// { +// // if (verbose) // printf("ERROR: index out of bounds\n"); +// } +// return -1.f; +//} + +float mavlink_wpm_distance_to_point(uint16_t seq, float x, float y, float z) +{ +// if (seq < wpm.size) +// { +// mavlink_mission_item_t *cur = waypoints->at(seq); +// +// const PxVector3 A(cur->x, cur->y, cur->z); +// const PxVector3 C(x, y, z); +// +// return (C-A).length(); +// } +// else +// { +// // if (verbose) // printf("ERROR: index out of bounds\n"); +// } + return -1.f; +} + +void mavlink_wpm_loop() +{ + //check for timed-out operations + uint64_t now = mavlink_missionlib_get_system_timestamp(); + if (now-wpm.timestamp_lastaction > wpm.timeout && wpm.current_state != MAVLINK_WPM_STATE_IDLE) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("Operation timeout switching -> IDLE"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm.current_state); +#endif + wpm.current_state = MAVLINK_WPM_STATE_IDLE; + wpm.current_count = 0; + wpm.current_partner_sysid = 0; + wpm.current_partner_compid = 0; + wpm.current_wp_id = -1; + + if(wpm.size == 0) + { + wpm.current_active_wp_id = -1; + } + } + + if(now-wpm.timestamp_last_send_setpoint > wpm.delay_setpoint && wpm.current_active_wp_id < wpm.size) + { + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + } +} + +void mavlink_wpm_message_handler(const mavlink_message_t* msg) +{ + uint64_t now = mavlink_missionlib_get_system_timestamp(); + switch(msg->msgid) + { + case MAVLINK_MSG_ID_ATTITUDE: + { + if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size) + { + mavlink_mission_item_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); + if(wp->frame == MAV_FRAME_LOCAL_ENU || wp->frame == MAV_FRAME_LOCAL_NED) + { + mavlink_attitude_t att; + mavlink_msg_attitude_decode(msg, &att); + float yaw_tolerance = wpm.accept_range_yaw; + //compare current yaw + if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI) + { + if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4) + wpm.yaw_reached = true; + } + else if(att.yaw - yaw_tolerance < 0.0f) + { + float lowerBound = 360.0f + att.yaw - yaw_tolerance; + if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance) + wpm.yaw_reached = true; + } + else + { + float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI; + if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound) + wpm.yaw_reached = true; + } + } + } + break; + } + + case MAVLINK_MSG_ID_LOCAL_POSITION_NED: + { + if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size) + { + mavlink_mission_item_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); + + if(wp->frame == MAV_FRAME_LOCAL_ENU || MAV_FRAME_LOCAL_NED) + { + mavlink_local_position_ned_t pos; + mavlink_msg_local_position_ned_decode(msg, &pos); + //// if (debug) // printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z); + + wpm.pos_reached = false; + + // compare current position (given in message) with current waypoint + float orbit = wp->param1; + + float dist; +// if (wp->param2 == 0) +// { +// // FIXME segment distance +// //dist = mavlink_wpm_distance_to_segment(current_active_wp_id, pos.x, pos.y, pos.z); +// } +// else +// { + dist = mavlink_wpm_distance_to_point(wpm.current_active_wp_id, pos.x, pos.y, pos.z); +// } + + if (dist >= 0.f && dist <= orbit && wpm.yaw_reached) + { + wpm.pos_reached = true; + } + } + } + break; + } + +// case MAVLINK_MSG_ID_CMD: // special action from ground station +// { +// mavlink_cmd_t action; +// mavlink_msg_cmd_decode(msg, &action); +// if(action.target == mavlink_system.sysid) +// { +// // if (verbose) std::cerr << "Waypoint: received message with action " << action.action << std::endl; +// switch (action.action) +// { +// // case MAV_ACTION_LAUNCH: +// // // if (verbose) std::cerr << "Launch received" << std::endl; +// // current_active_wp_id = 0; +// // if (wpm.size>0) +// // { +// // setActive(waypoints[current_active_wp_id]); +// // } +// // else +// // // if (verbose) std::cerr << "No launch, waypointList empty" << std::endl; +// // break; +// +// // case MAV_ACTION_CONTINUE: +// // // if (verbose) std::c +// // err << "Continue received" << std::endl; +// // idle = false; +// // setActive(waypoints[current_active_wp_id]); +// // break; +// +// // case MAV_ACTION_HALT: +// // // if (verbose) std::cerr << "Halt received" << std::endl; +// // idle = true; +// // break; +// +// // default: +// // // if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl; +// // break; +// } +// } +// break; +// } + + case MAVLINK_MSG_ID_MISSION_ACK: + { + mavlink_mission_ack_t wpa; + mavlink_msg_mission_ack_decode(msg, &wpa); + + if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/)) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) + { + if (wpm.current_wp_id == wpm.size-1) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Received ACK after having sent last waypoint, going to state MAVLINK_WPM_STATE_IDLE\n"); +#endif + wpm.current_state = MAVLINK_WPM_STATE_IDLE; + wpm.current_wp_id = 0; + } + } + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch"); +#else + if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); +#endif + } + break; + } + + case MAVLINK_MSG_ID_MISSION_SET_CURRENT: + { + mavlink_mission_set_current_t wpc; + mavlink_msg_mission_set_current_decode(msg, &wpc); + + if(wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { + if (wpc.seq < wpm.size) + { + // if (verbose) // printf("Received MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT\n"); + wpm.current_active_wp_id = wpc.seq; + uint32_t i; + for(i = 0; i < wpm.size; i++) + { + if (i == wpm.current_active_wp_id) + { + wpm.waypoints[i].current = true; + } + else + { + wpm.waypoints[i].current = false; + } + } +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("NEW WP SET"); +#else + if (MAVLINK_WPM_VERBOSE) printf("New current waypoint %u\n", wpm.current_active_wp_id); +#endif + wpm.yaw_reached = false; + wpm.pos_reached = false; + mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id); + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + wpm.timestamp_firstinside_orbit = 0; + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT: Index out of bounds\n"); +#endif + } + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy"); +#else + if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE NOT IN IDLE STATE\n"); +#endif + } + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch"); +#else + if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); +#endif + } + break; + } + + case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: + { + mavlink_mission_request_list_t wprl; + mavlink_msg_mission_request_list_decode(msg, &wprl); + if(wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) + { + if (wpm.size > 0) + { + //if (verbose && wpm.current_state == MAVLINK_WPM_STATE_IDLE) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); + wpm.current_state = MAVLINK_WPM_STATE_SENDLIST; + wpm.current_wp_id = 0; + wpm.current_partner_sysid = msg->sysid; + wpm.current_partner_compid = msg->compid; + } + else + { + // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid); + } + wpm.current_count = wpm.size; + mavlink_wpm_send_waypoint_count(msg->sysid,msg->compid, wpm.current_count); + } + else + { + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).\n", wpm.current_state); + } + } + else + { + // if (verbose) // printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT MISMATCH\n"); + } + + break; + } + + case MAVLINK_MSG_ID_MISSION_REQUEST: + { + mavlink_mission_request_t wpr; + mavlink_msg_mission_request_decode(msg, &wpr); + if(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid && wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) + { + wpm.timestamp_lastaction = now; + + //ensure that we are in the correct state and that the first request has id 0 and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint) + if ((wpm.current_state == MAVLINK_WPM_STATE_SENDLIST && wpr.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && (wpr.seq == wpm.current_wp_id || wpr.seq == wpm.current_wp_id + 1) && wpr.seq < wpm.size)) + { + if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("GOT WP REQ, state -> SEND"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); +#endif + } + if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id + 1) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); +#endif + } + if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); +#endif + } + + wpm.current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; + wpm.current_wp_id = wpr.seq; + mavlink_wpm_send_waypoint(wpm.current_partner_sysid, wpm.current_partner_compid, wpr.seq); + } + else + { + // if (verbose) + { + if (!(wpm.current_state == MAVLINK_WPM_STATE_SENDLIST || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS)) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).\n", wpm.current_state); +#endif + break; + } + else if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) + { + if (wpr.seq != 0) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq); +#endif + } + } + else if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) + { + if (wpr.seq != wpm.current_wp_id && wpr.seq != wpm.current_wp_id + 1) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, wpm.current_wp_id, wpm.current_wp_id+1); +#endif + } + else if (wpr.seq >= wpm.size) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq); +#endif + } + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST - FIXME: missed error description\n"); +#endif + } + } + } + } + else + { + //we we're target but already communicating with someone else + if((wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid)) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, wpm.current_partner_sysid); +#endif + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch"); +#else + if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); +#endif + } + + } + break; + } + + case MAVLINK_MSG_ID_MISSION_COUNT: + { + mavlink_mission_count_t wpc; + mavlink_msg_mission_count_decode(msg, &wpc); + if(wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) + { + wpm.timestamp_lastaction = now; + + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id == 0)) + { + if (wpc.count > 0) + { + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("WP CMD OK: state -> GETLIST"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST\n", wpc.count, msg->sysid); +#endif + } + if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u\n", wpc.count, msg->sysid); +#endif + } + + wpm.current_state = MAVLINK_WPM_STATE_GETLIST; + wpm.current_wp_id = 0; + wpm.current_partner_sysid = msg->sysid; + wpm.current_partner_compid = msg->compid; + wpm.current_count = wpc.count; + +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("CLR RCV BUF: READY"); +#else + if (MAVLINK_WPM_VERBOSE) printf("clearing receive buffer and readying for receiving waypoints\n"); +#endif + wpm.rcv_size = 0; + //while(waypoints_receive_buffer->size() > 0) +// { +// delete waypoints_receive_buffer->back(); +// waypoints_receive_buffer->pop_back(); +// } + + mavlink_wpm_send_waypoint_request(wpm.current_partner_sysid, wpm.current_partner_compid, wpm.current_wp_id); + } + else if (wpc.count == 0) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("COUNT 0"); +#else + if (MAVLINK_WPM_VERBOSE) printf("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE\n"); +#endif + wpm.rcv_size = 0; + //while(waypoints_receive_buffer->size() > 0) +// { +// delete waypoints->back(); +// waypoints->pop_back(); +// } + wpm.current_active_wp_id = -1; + wpm.yaw_reached = false; + wpm.pos_reached = false; + break; + + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("IGN WP CMD"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignoring MAVLINK_MSG_ID_MISSION_ITEM_COUNT from %u with count of %u\n", msg->sysid, wpc.count); +#endif + } + } + else + { + if (!(wpm.current_state == MAVLINK_WPM_STATE_IDLE || wpm.current_state == MAVLINK_WPM_STATE_GETLIST)) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm doing something else already (state=%i).\n", wpm.current_state); +#endif + } + else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id != 0) + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.\n", wpm.current_wp_id); +#endif + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?"); +#else + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT - FIXME: missed error description\n"); +#endif + } + } + } + else + { +#ifdef MAVLINK_WPM_NO_PRINTF + mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch"); +#else + if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n"); +#endif + } + + } + break; + + case MAVLINK_MSG_ID_MISSION_ITEM: + { + mavlink_mission_item_t wp; + mavlink_msg_mission_item_decode(msg, &wp); + + mavlink_missionlib_send_gcs_string("GOT WP"); + + if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/)) + { + wpm.timestamp_lastaction = now; + + //ensure that we are in the correct state and that the first waypoint has id 0 and the following waypoints have the correct ids + if ((wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wp.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id && wp.seq < wpm.current_count)) + { +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u\n", wp.seq, msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq-1 == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u (again) from %u\n", wp.seq, msg->sysid); +// + wpm.current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS; + mavlink_mission_item_t* newwp = &(wpm.rcv_waypoints[wp.seq]); + memcpy(newwp, &wp, sizeof(mavlink_mission_item_t)); + wpm.current_wp_id = wp.seq + 1; + + // if (verbose) // printf ("Added new waypoint to list. X= %f\t Y= %f\t Z= %f\t Yaw= %f\n", newwp->x, newwp->y, newwp->z, newwp->param4); + + if(wpm.current_wp_id == wpm.current_count && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) + { + mavlink_missionlib_send_gcs_string("GOT ALL WPS"); + // if (verbose) // printf("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm.current_count); + + mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0); + + if (wpm.current_active_wp_id > wpm.rcv_size-1) + { + wpm.current_active_wp_id = wpm.rcv_size-1; + } + + // switch the waypoints list + // FIXME CHECK!!! + for (int i = 0; i < wpm.current_count; ++i) + { + wpm.waypoints[i] = wpm.rcv_waypoints[i]; + } + wpm.size = wpm.current_count; + + //get the new current waypoint + uint32_t i; + for(i = 0; i < wpm.size; i++) + { + if (wpm.waypoints[i].current == 1) + { + wpm.current_active_wp_id = i; + //// if (verbose) // printf("New current waypoint %u\n", current_active_wp_id); + wpm.yaw_reached = false; + wpm.pos_reached = false; + mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id); + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + wpm.timestamp_firstinside_orbit = 0; + break; + } + } + + if (i == wpm.size) + { + wpm.current_active_wp_id = -1; + wpm.yaw_reached = false; + wpm.pos_reached = false; + wpm.timestamp_firstinside_orbit = 0; + } + + wpm.current_state = MAVLINK_WPM_STATE_IDLE; + } + else + { + mavlink_wpm_send_waypoint_request(wpm.current_partner_sysid, wpm.current_partner_compid, wpm.current_wp_id); + } + } + else + { + if (wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { + //we're done receiving waypoints, answer with ack. + mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0); + // printf("Received MAVLINK_MSG_ID_MISSION_ITEM while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n"); + } + // if (verbose) + { + if (!(wpm.current_state == MAVLINK_WPM_STATE_GETLIST || wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)) + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u because i'm doing something else already (state=%i).\n", wp.seq, wpm.current_state); + break; + } + else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST) + { + if(!(wp.seq == 0)) + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.\n", wp.seq); + } + else + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq); + } + } + else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) + { + if (!(wp.seq == wpm.current_wp_id)) + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm.current_wp_id); + } + else if (!(wp.seq < wpm.current_count)) + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.\n", wp.seq); + } + else + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq); + } + } + else + { + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq); + } + } + } + } + else + { + //we we're target but already communicating with someone else + if((wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && wpm.current_state != MAVLINK_WPM_STATE_IDLE) + { + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm.current_partner_sysid); + } + else if(wp.target_system == mavlink_system.sysid /* && wp.target_component == mavlink_wpm_comp_id*/) + { + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid); + } + } + break; + } + + case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: + { + mavlink_mission_clear_all_t wpca; + mavlink_msg_mission_clear_all_decode(msg, &wpca); + + if(wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm.current_state == MAVLINK_WPM_STATE_IDLE) + { + wpm.timestamp_lastaction = now; + + // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid); + // Delete all waypoints + wpm.size = 0; + wpm.current_active_wp_id = -1; + wpm.yaw_reached = false; + wpm.pos_reached = false; + } + else if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm.current_state != MAVLINK_WPM_STATE_IDLE) + { + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, wpm.current_state); + } + break; + } + + default: + { + // if (debug) // printf("Waypoint: received message of unknown type"); + break; + } + } + + //check if the current waypoint was reached + if (wpm.pos_reached /*wpm.yaw_reached &&*/ && !wpm.idle) + { + if (wpm.current_active_wp_id < wpm.size) + { + mavlink_mission_item_t *cur_wp = &(wpm.waypoints[wpm.current_active_wp_id]); + + if (wpm.timestamp_firstinside_orbit == 0) + { + // Announce that last waypoint was reached + // if (verbose) // printf("*** Reached waypoint %u ***\n", cur_wp->seq); + mavlink_wpm_send_waypoint_reached(cur_wp->seq); + wpm.timestamp_firstinside_orbit = now; + } + + // check if the MAV was long enough inside the waypoint orbit + //if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000)) + if(now-wpm.timestamp_firstinside_orbit >= cur_wp->param2*1000) + { + if (cur_wp->autocontinue) + { + cur_wp->current = 0; + if (wpm.current_active_wp_id == wpm.size - 1 && wpm.size > 1) + { + //the last waypoint was reached, if auto continue is + //activated restart the waypoint list from the beginning + wpm.current_active_wp_id = 1; + } + else + { + if ((uint16_t)(wpm.current_active_wp_id + 1) < wpm.size) + wpm.current_active_wp_id++; + } + + // Fly to next waypoint + wpm.timestamp_firstinside_orbit = 0; + mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id); + mavlink_wpm_send_setpoint(wpm.current_active_wp_id); + wpm.waypoints[wpm.current_active_wp_id].current = true; + wpm.pos_reached = false; + wpm.yaw_reached = false; + // if (verbose) // printf("Set new waypoint (%u)\n", wpm.current_active_wp_id); + } + } + } + } + else + { + wpm.timestamp_lastoutside_orbit = now; + } +} + diff --git a/missionlib/waypoints.h b/missionlib/waypoints.h new file mode 100644 index 0000000..49374f6 --- /dev/null +++ b/missionlib/waypoints.h @@ -0,0 +1,104 @@ +/******************************************************************************* + + Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch + + 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 . + + ****************************************************************************/ + +/* This assumes you have the mavlink headers on your include path + or in the same folder as this source file */ + +// Disable auto-data structures +#ifndef MAVLINK_NO_DATA +#define MAVLINK_NO_DATA +#endif + +#include +extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t* buffer, uint16_t len); + +#ifndef MAVLINK_SEND_UART_BYTES +#define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len) +#endif +extern mavlink_system_t mavlink_system; +#include +#include + +// FIXME XXX - TO BE MOVED TO XML +enum MAVLINK_WPM_STATES +{ + MAVLINK_WPM_STATE_IDLE = 0, + MAVLINK_WPM_STATE_SENDLIST, + MAVLINK_WPM_STATE_SENDLIST_SENDWPS, + MAVLINK_WPM_STATE_GETLIST, + MAVLINK_WPM_STATE_GETLIST_GETWPS, + MAVLINK_WPM_STATE_GETLIST_GOTALL, + MAVLINK_WPM_STATE_ENUM_END +}; + +enum MAVLINK_WPM_CODES +{ + MAVLINK_WPM_CODE_OK = 0, + MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS, + MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, + MAVLINK_WPM_CODE_ENUM_END +}; + + +/* WAYPOINT MANAGER - MISSION LIB */ + +#define MAVLINK_WPM_MAX_WP_COUNT 15 +#define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates +#ifndef MAVLINK_WPM_TEXT_FEEDBACK +#define MAVLINK_WPM_TEXT_FEEDBACK 0 ///< Report back status information as text +#endif +#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000 ///< Protocol communication timeout in milliseconds +#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000 ///< When to send a new setpoint +#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40 + + +struct mavlink_wpm_storage { + mavlink_mission_item_t waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Currently active waypoints +#ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE + mavlink_mission_item_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints +#endif + uint16_t size; + uint16_t max_size; + uint16_t rcv_size; + enum MAVLINK_WPM_STATES current_state; + uint16_t current_wp_id; ///< Waypoint in current transmission + uint16_t current_active_wp_id; ///< Waypoint the system is currently heading towards + uint16_t current_count; + uint8_t current_partner_sysid; + uint8_t current_partner_compid; + uint64_t timestamp_lastaction; + uint64_t timestamp_last_send_setpoint; + uint64_t timestamp_firstinside_orbit; + uint64_t timestamp_lastoutside_orbit; + uint32_t timeout; + uint32_t delay_setpoint; + float accept_range_yaw; + float accept_range_distance; + bool yaw_reached; + bool pos_reached; + bool idle; +}; + +typedef struct mavlink_wpm_storage mavlink_wpm_storage; + +void mavlink_wpm_init(mavlink_wpm_storage* state); +void mavlink_wpm_loop(); +void mavlink_wpm_message_handler(const mavlink_message_t* msg); diff --git a/package.xml b/package.xml new file mode 100644 index 0000000..9d162a2 --- /dev/null +++ b/package.xml @@ -0,0 +1,26 @@ + + + mavlink + 2016.4.4 + MAVLink message marshaling library. + This package provides C-headers and pymavlink library. + + + Vladimir Ermakov + + http://qgroundcontrol.org/mavlink/ + https://github.com/mavlink/mavlink.git + https://github.com/mavlink/mavlink/issues + + Lorenz Meier + LGPLv3 + + python + catkin + python + cmake + + + cmake + + diff --git a/pc.in b/pc.in new file mode 100644 index 0000000..77a4548 --- /dev/null +++ b/pc.in @@ -0,0 +1,8 @@ +prefix=@CMAKE_INSTALL_PREFIX@ +exec_prefix=@CMAKE_INSTALL_PREFIX@ +includedir=${prefix}/include + +Name: @PKG_NAME@ +Description: @PKG_DESC@ +Version: @PKG_VERSION@ +Cflags: -I${includedir} diff --git a/pymavlink/APM_Mavtest/APM_Mavtest.pde b/pymavlink/APM_Mavtest/APM_Mavtest.pde new file mode 100644 index 0000000..b903b5c --- /dev/null +++ b/pymavlink/APM_Mavtest/APM_Mavtest.pde @@ -0,0 +1,55 @@ +/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- + +/* + send all possible mavlink messages + Andrew Tridgell July 2011 +*/ + +// AVR runtime +#include +#include +#include +#include + +// Libraries +#include +#include +#include +#include "mavtest.h" + +FastSerialPort0(Serial); // FTDI/console +FastSerialPort1(Serial1); // GPS port +FastSerialPort3(Serial3); // Telemetry port + +#define SERIAL0_BAUD 115200 +#define SERIAL3_BAUD 115200 + +void setup() { + Serial.begin(SERIAL0_BAUD, 128, 128); + Serial3.begin(SERIAL3_BAUD, 128, 128); + mavlink_comm_0_port = &Serial; + mavlink_comm_1_port = &Serial3; +} + + + +void loop() +{ + Serial.println("Starting MAVLink test generator\n"); + while (1) { + mavlink_msg_heartbeat_send( + MAVLINK_COMM_0, + mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); + + mavlink_msg_heartbeat_send( + MAVLINK_COMM_1, + mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); + + mavtest_generate_outputs(MAVLINK_COMM_0); + mavtest_generate_outputs(MAVLINK_COMM_1); + delay(500); + } +} + diff --git a/pymavlink/APM_Mavtest/Makefile b/pymavlink/APM_Mavtest/Makefile new file mode 100644 index 0000000..7ca38b1 --- /dev/null +++ b/pymavlink/APM_Mavtest/Makefile @@ -0,0 +1,10 @@ +# +# Trivial makefile for building APM +# + +# +# Select 'mega' for the original APM, or 'mega2560' for the V2 APM. +# +BOARD = mega2560 + +include ../libraries/AP_Common/Arduino.mk diff --git a/pymavlink/CMakeLists.txt b/pymavlink/CMakeLists.txt new file mode 100644 index 0000000..f1063a8 --- /dev/null +++ b/pymavlink/CMakeLists.txt @@ -0,0 +1,29 @@ +# pymavlink support's python2 only +set(PythonInterp_FIND_VERSION "2") +find_package(PythonInterp REQUIRED) + +# part of catkin/python.cmake +set(enable_setuptools_deb_layout OFF) +if(EXISTS "/etc/debian_version") + set(enable_setuptools_deb_layout ON) +endif() +option(SETUPTOOLS_DEB_LAYOUT "Enable debian style python package layout" ${enable_setuptools_deb_layout}) + +if(SETUPTOOLS_DEB_LAYOUT) + message(STATUS "Using Debian Python package layout") + set(SETUPTOOLS_ARG_EXTRA "--install-layout=deb") +else() + message(STATUS "Using default Python package layout") +endif() + +# prepare installation script +set(INSTALL_SCRIPT_TMP ${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/python_distutils_install.sh) +set(INSTALL_SCRIPT ${CMAKE_CURRENT_BINARY_DIR}/python_distutils_install.sh) +configure_file(python_distutils_install.sh.in ${INSTALL_SCRIPT_TMP} @ONLY) + +# workaround for setting exec perms on install script +file(COPY ${INSTALL_SCRIPT_TMP} DESTINATION ${CMAKE_CURRENT_BINARY_DIR} + FILE_PERMISSIONS OWNER_READ OWNER_WRITE OWNER_EXECUTE GROUP_READ GROUP_EXECUTE WORLD_READ WORLD_EXECUTE +) + +install(CODE "execute_process(COMMAND \"${INSTALL_SCRIPT}\" WORKING_DIRECTORY \"${CMAKE_CURRENT_SOURCE_DIR}\")") diff --git a/pymavlink/DFReader.py b/pymavlink/DFReader.py new file mode 100644 index 0000000..86b4af9 --- /dev/null +++ b/pymavlink/DFReader.py @@ -0,0 +1,702 @@ +#!/usr/bin/env python +''' +APM DataFlash log file reader + +Copyright Andrew Tridgell 2011 +Released under GNU GPL version 3 or later + +Partly based on SDLog2Parser by Anton Babushkin +''' + +import struct, time, os +from . import mavutil + +FORMAT_TO_STRUCT = { + "b": ("b", None, int), + "B": ("B", None, int), + "h": ("h", None, int), + "H": ("H", None, int), + "i": ("i", None, int), + "I": ("I", None, int), + "f": ("f", None, float), + "n": ("4s", None, str), + "N": ("16s", None, str), + "Z": ("64s", None, str), + "c": ("h", 0.01, float), + "C": ("H", 0.01, float), + "e": ("i", 0.01, float), + "E": ("I", 0.01, float), + "L": ("i", 1.0e-7, float), + "d": ("d", None, float), + "M": ("b", None, int), + "q": ("q", None, long), + "Q": ("Q", None, long), + } + +class DFFormat(object): + def __init__(self, type, name, flen, format, columns): + self.type = type + self.name = name + self.len = flen + self.format = format + self.columns = columns.split(',') + + if self.columns == ['']: + self.columns = [] + + msg_struct = "<" + msg_mults = [] + msg_types = [] + for c in format: + if ord(c) == 0: + break + try: + (s, mul, type) = FORMAT_TO_STRUCT[c] + msg_struct += s + msg_mults.append(mul) + msg_types.append(type) + except KeyError as e: + raise Exception("Unsupported format char: '%s' in message %s" % (c, name)) + + self.msg_struct = msg_struct + self.msg_types = msg_types + self.msg_mults = msg_mults + self.colhash = {} + for i in range(len(self.columns)): + self.colhash[self.columns[i]] = i + + def __str__(self): + return "DFFormat(%s,%s,%s,%s)" % (self.type, self.name, self.format, self.columns) + +def null_term(str): + '''null terminate a string''' + idx = str.find("\0") + if idx != -1: + str = str[:idx] + return str + +class DFMessage(object): + def __init__(self, fmt, elements, apply_multiplier): + self.fmt = fmt + self._elements = elements + self._apply_multiplier = apply_multiplier + self._fieldnames = fmt.columns + + def to_dict(self): + d = {'mavpackettype': self.fmt.name} + + for field in self._fieldnames: + d[field] = self.__getattr__(field) + + return d + + def __getattr__(self, field): + '''override field getter''' + try: + i = self.fmt.colhash[field] + except Exception: + raise AttributeError(field) + v = self._elements[i] + if self.fmt.format[i] != 'M' or self._apply_multiplier: + v = self.fmt.msg_types[i](v) + if self.fmt.msg_types[i] == str: + v = null_term(v) + if self.fmt.msg_mults[i] is not None and self._apply_multiplier: + v *= self.fmt.msg_mults[i] + return v + + def get_type(self): + return self.fmt.name + + def __str__(self): + ret = "%s {" % self.fmt.name + col_count = 0 + for c in self.fmt.columns: + ret += "%s : %s, " % (c, self.__getattr__(c)) + col_count += 1 + if col_count != 0: + ret = ret[:-2] + return ret + '}' + + def get_msgbuf(self): + '''create a binary message buffer for a message''' + values = [] + for i in range(len(self.fmt.columns)): + if i >= len(self.fmt.msg_mults): + continue + mul = self.fmt.msg_mults[i] + name = self.fmt.columns[i] + if name == 'Mode' and 'ModeNum' in self.fmt.columns: + name = 'ModeNum' + v = self.__getattr__(name) + if mul is not None: + v /= mul + values.append(v) + return struct.pack("BBB", 0xA3, 0x95, self.fmt.type) + struct.pack(self.fmt.msg_struct, *values) + + def get_fieldnames(self): + return self._fieldnames + +class DFReaderClock(): + '''base class for all the different ways we count time in logs''' + + def __init__(self): + self.set_timebase(0) + self.timestamp = 0 + + def _gpsTimeToTime(self, week, msec): + '''convert GPS week and TOW to a time in seconds since 1970''' + epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2) + return epoch + 86400*7*week + msec*0.001 - 15 + + def set_timebase(self, base): + self.timebase = base + + def message_arrived(self, m): + pass + + def rewind_event(self): + pass + +class DFReaderClock_usec(DFReaderClock): + '''DFReaderClock_usec - use microsecond timestamps from messages''' + def __init__(self): + DFReaderClock.__init__(self) + + def find_time_base(self, gps, first_us_stamp): + '''work out time basis for the log - even newer style''' + t = self._gpsTimeToTime(gps.GWk, gps.GMS) + self.set_timebase(t - gps.TimeUS*0.000001) + # this ensures FMT messages get appropriate timestamp: + self.timestamp = self.timebase + first_us_stamp*0.000001 + + def type_has_good_TimeMS(self, type): + '''The TimeMS in some messages is not from *our* clock!''' + if type.startswith('ACC'): + return False; + if type.startswith('GYR'): + return False; + return True + + def should_use_msec_field0(self, m): + if not self.type_has_good_TimeMS(m.get_type()): + return False + if 'TimeMS' != m._fieldnames[0]: + return False + if self.timebase + m.TimeMS*0.001 < self.timestamp: + return False + return True; + + def set_message_timestamp(self, m): + if 'TimeUS' == m._fieldnames[0]: + # only format messages don't have a TimeUS in them... + m._timestamp = self.timebase + m.TimeUS*0.000001 + elif self.should_use_msec_field0(m): + # ... in theory. I expect there to be some logs which are not + # "pure": + m._timestamp = self.timebase + m.TimeMS*0.001 + else: + m._timestamp = self.timestamp + self.timestamp = m._timestamp + +class DFReaderClock_msec(DFReaderClock): + '''DFReaderClock_msec - a format where many messages have TimeMS in their formats, and GPS messages have a "T" field giving msecs ''' + def find_time_base(self, gps, first_ms_stamp): + '''work out time basis for the log - new style''' + t = self._gpsTimeToTime(gps.Week, gps.TimeMS) + self.set_timebase(t - gps.T*0.001) + self.timestamp = self.timebase + first_ms_stamp*0.001 + + def set_message_timestamp(self, m): + if 'TimeMS' == m._fieldnames[0]: + m._timestamp = self.timebase + m.TimeMS*0.001 + elif m.get_type() in ['GPS','GPS2']: + m._timestamp = self.timebase + m.T*0.001 + else: + m._timestamp = self.timestamp + self.timestamp = m._timestamp + +class DFReaderClock_px4(DFReaderClock): + '''DFReaderClock_px4 - a format where a starting time is explicitly given in a message''' + def __init__(self): + DFReaderClock.__init__(self) + self.px4_timebase = 0 + + def find_time_base(self, gps): + '''work out time basis for the log - PX4 native''' + t = gps.GPSTime * 1.0e-6 + self.timebase = t - self.px4_timebase + + def set_px4_timebase(self, time_msg): + self.px4_timebase = time_msg.StartTime * 1.0e-6 + + def set_message_timestamp(self, m): + m._timestamp = self.timebase + self.px4_timebase + + def message_arrived(self, m): + type = m.get_type() + if type == 'TIME' and 'StartTime' in m._fieldnames: + self.set_px4_timebase(m) + +class DFReaderClock_gps_interpolated(DFReaderClock): + '''DFReaderClock_gps_interpolated - for when the only real references in a message are GPS timestamps ''' + def __init__(self): + DFReaderClock.__init__(self) + self.msg_rate = {} + self.counts = {} + self.counts_since_gps = {} + + def rewind_event(self): + '''reset counters on rewind''' + self.counts = {} + self.counts_since_gps = {} + + def message_arrived(self, m): + type = m.get_type() + if not type in self.counts: + self.counts[type] = 1 + else: + self.counts[type] += 1 + # this preserves existing behaviour - but should we be doing this + # if type == 'GPS'? + if not type in self.counts_since_gps: + self.counts_since_gps[type] = 1 + else: + self.counts_since_gps[type] += 1 + + if type == 'GPS' or type == 'GPS2': + self.gps_message_arrived(m) + + def gps_message_arrived(self, m): + '''adjust time base from GPS message''' + # msec-style GPS message? + gps_week = getattr(m, 'Week', None) + gps_timems = getattr(m, 'TimeMS', None) + if gps_week is None: + # usec-style GPS message? + gps_week = getattr(m, 'GWk', None) + gps_timems = getattr(m, 'GMS', None) + if gps_week is None: + if getattr(m, 'GPSTime', None) is not None: + # PX4-style timestamp; we've only been called + # because we were speculatively created in case no + # better clock was found. + return; + + t = self._gpsTimeToTime(gps_week, gps_timems) + + deltat = t - self.timebase + if deltat <= 0: + return + + for type in self.counts_since_gps: + rate = self.counts_since_gps[type] / deltat + if rate > self.msg_rate.get(type, 0): + self.msg_rate[type] = rate + self.msg_rate['IMU'] = 50.0 + self.timebase = t + self.counts_since_gps = {} + + def set_message_timestamp(self, m): + rate = self.msg_rate.get(m.fmt.name, 50.0) + if int(rate) == 0: + rate = 50 + count = self.counts_since_gps.get(m.fmt.name, 0) + m._timestamp = self.timebase + count/rate + + +class DFReader(object): + '''parse a generic dataflash file''' + def __init__(self): + # read the whole file into memory for simplicity + self.clock = None + self.timestamp = 0 + self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING + self.verbose = False + self.params = {} + + def _rewind(self): + '''reset state on rewind''' + self.messages = { 'MAV' : self } + self.flightmode = "UNKNOWN" + self.percent = 0 + if self.clock: + self.clock.rewind_event() + + def init_clock_px4(self, px4_msg_time, px4_msg_gps): + self.clock = DFReaderClock_px4() + if not self._zero_time_base: + self.clock.set_px4_timebase(px4_msg_time) + self.clock.find_time_base(px4_msg_gps) + return True + + def init_clock_msec(self): + # it is a new style flash log with full timestamps + self.clock = DFReaderClock_msec() + + def init_clock_usec(self): + self.clock = DFReaderClock_usec() + + def init_clock_gps_interpolated(self, clock): + self.clock = clock + + def init_clock(self): + '''work out time basis for the log''' + + self._rewind() + + # speculatively create a gps clock in case we don't find anything + # better + gps_clock = DFReaderClock_gps_interpolated() + self.clock = gps_clock + + px4_msg_time = None + px4_msg_gps = None + gps_interp_msg_gps1 = None + gps_interp_msg_gps2 = None + first_us_stamp = None + first_ms_stamp = None + + have_good_clock = False + while True: + m = self.recv_msg() + if m is None: + break; + + type = m.get_type() + + if first_us_stamp is None: + first_us_stamp = getattr(m, "TimeUS", None); + + if first_ms_stamp is None and (type != 'GPS' and type != 'GPS2'): + # Older GPS messages use TimeMS for msecs past start + # of gps week + first_ms_stamp = getattr(m, "TimeMS", None); + + if type == 'GPS' or type == 'GPS2': + if getattr(m, "TimeUS", 0) != 0 and \ + getattr(m, "GWk", 0) != 0: # everything-usec-timestamped + self.init_clock_usec() + if not self._zero_time_base: + self.clock.find_time_base(m, first_us_stamp) + have_good_clock = True + break + if getattr(m, "T", 0) != 0 and \ + getattr(m, "Week", 0) != 0: # GPS is msec-timestamped + if first_ms_stamp is None: + first_ms_stamp = m.T + self.init_clock_msec() + if not self._zero_time_base: + self.clock.find_time_base(m, first_ms_stamp) + have_good_clock = True + break + if getattr(m, "GPSTime", 0) != 0: # px4-style-only + px4_msg_gps = m + if getattr(m, "Week", 0) != 0: + if gps_interp_msg_gps1 is not None and \ + (gps_interp_msg_gps1.TimeMS != m.TimeMS or \ + gps_interp_msg_gps1.Week != m.Week): + # we've received two distinct, non-zero GPS + # packets without finding a decent clock to + # use; fall back to interpolation. Q: should + # we wait a few more messages befoe doing + # this? + self.init_clock_gps_interpolated(gps_clock) + have_good_clock = True + break + gps_interp_msg_gps1 = m + + elif type == 'TIME': + '''only px4-style logs use TIME''' + if getattr(m, "StartTime", None) != None: + px4_msg_time = m; + + if px4_msg_time is not None and px4_msg_gps is not None: + self.init_clock_px4(px4_msg_time, px4_msg_gps) + have_good_clock = True + break + +# print("clock is " + str(self.clock)) + if not have_good_clock: + # we failed to find any GPS messages to set a time + # base for usec and msec clocks. Also, not a + # PX4-style log + if first_us_stamp is not None: + self.init_clock_usec() + elif first_ms_stamp is not None: + self.init_clock_msec() + + self._rewind() + + return + + def _set_time(self, m): + '''set time for a message''' + # really just left here for profiling + m._timestamp = self.timestamp + if len(m._fieldnames) > 0 and self.clock is not None: + self.clock.set_message_timestamp(m) + + def recv_msg(self): + return self._parse_next() + + def _add_msg(self, m): + '''add a new message''' + type = m.get_type() + self.messages[type] = m + + if self.clock: + self.clock.message_arrived(m) + + if type == 'MSG': + if m.Message.find("Rover") != -1: + self.mav_type = mavutil.mavlink.MAV_TYPE_GROUND_ROVER + elif m.Message.find("Plane") != -1: + self.mav_type = mavutil.mavlink.MAV_TYPE_FIXED_WING + elif m.Message.find("Copter") != -1: + self.mav_type = mavutil.mavlink.MAV_TYPE_QUADROTOR + elif m.Message.startswith("Antenna"): + self.mav_type = mavutil.mavlink.MAV_TYPE_ANTENNA_TRACKER + if type == 'MODE': + if isinstance(m.Mode, str): + self.flightmode = m.Mode.upper() + elif 'ModeNum' in m._fieldnames: + mapping = mavutil.mode_mapping_bynumber(self.mav_type) + if mapping is not None and m.ModeNum in mapping: + self.flightmode = mapping[m.ModeNum] + else: + self.flightmode = mavutil.mode_string_acm(m.Mode) + if type == 'STAT' and 'MainState' in m._fieldnames: + self.flightmode = mavutil.mode_string_px4(m.MainState) + if type == 'PARM' and getattr(m, 'Name', None) is not None: + self.params[m.Name] = m.Value + self._set_time(m) + + def recv_match(self, condition=None, type=None, blocking=False): + '''recv the next message that matches the given condition + type can be a string or a list of strings''' + if type is not None and not isinstance(type, list): + type = [type] + while True: + m = self.recv_msg() + if m is None: + return None + if type is not None and not m.get_type() in type: + continue + if not mavutil.evaluate_condition(condition, self.messages): + continue + return m + + def check_condition(self, condition): + '''check if a condition is true''' + return mavutil.evaluate_condition(condition, self.messages) + + def param(self, name, default=None): + '''convenient function for returning an arbitrary MAVLink + parameter with a default''' + if not name in self.params: + return default + return self.params[name] + +class DFReader_binary(DFReader): + '''parse a binary dataflash file''' + def __init__(self, filename, zero_time_base=False): + DFReader.__init__(self) + # read the whole file into memory for simplicity + f = open(filename, mode='rb') + self.data = f.read() + self.data_len = len(self.data) + f.close() + self.HEAD1 = 0xA3 + self.HEAD2 = 0x95 + self.formats = { + 0x80 : DFFormat(0x80, 'FMT', 89, 'BBnNZ', "Type,Length,Name,Format,Columns") + } + self._zero_time_base = zero_time_base + self.init_clock() + self._rewind() + + def _rewind(self): + '''rewind to start of log''' + DFReader._rewind(self) + self.offset = 0 + self.remaining = self.data_len + + def _parse_next(self): + '''read one message, returning it as an object''' + if self.data_len - self.offset < 3: + return None + + hdr = self.data[self.offset:self.offset+3] + skip_bytes = 0 + skip_type = None + # skip over bad messages + while (ord(hdr[0]) != self.HEAD1 or ord(hdr[1]) != self.HEAD2 or ord(hdr[2]) not in self.formats): + if skip_type is None: + skip_type = (ord(hdr[0]), ord(hdr[1]), ord(hdr[2])) + skip_bytes += 1 + self.offset += 1 + if self.data_len - self.offset < 3: + return None + hdr = self.data[self.offset:self.offset+3] + msg_type = ord(hdr[2]) + if skip_bytes != 0: + if self.remaining < 528: + return None + print("Skipped %u bad bytes in log %s remaining=%u" % (skip_bytes, skip_type, self.remaining)) + self.remaining -= skip_bytes + + self.offset += 3 + self.remaining -= 3 + + if not msg_type in self.formats: + if self.verbose: + print("unknown message type %02x" % msg_type) + raise Exception("Unknown message type %02x" % msg_type) + fmt = self.formats[msg_type] + if self.remaining < fmt.len-3: + # out of data - can often happen half way through a message + if self.verbose: + print("out of data") + return None + body = self.data[self.offset:self.offset+(fmt.len-3)] + elements = None + try: + elements = list(struct.unpack(fmt.msg_struct, body)) + except Exception: + if self.remaining < 528: + # we can have garbage at the end of an APM2 log + return None + # we should also cope with other corruption; logs + # transfered via DataFlash_MAVLink may have blocks of 0s + # in them, for example + print("Failed to parse %s/%s with len %u (remaining %u)" % (fmt.name, fmt.msg_struct, len(body), self.remaining)) + if elements is None: + return self._parse_next() + name = null_term(fmt.name) + if name == 'FMT': + # add to formats + # name, len, format, headings + self.formats[elements[0]] = DFFormat(elements[0], + null_term(elements[2]), elements[1], + null_term(elements[3]), null_term(elements[4])) + + self.offset += fmt.len-3 + self.remaining -= fmt.len-3 + m = DFMessage(fmt, elements, True) + self._add_msg(m) + + self.percent = 100.0 * (self.offset / float(self.data_len)) + + return m + +def DFReader_is_text_log(filename): + '''return True if a file appears to be a valid text log''' + f = open(filename) + ret = (f.read(8000).find('FMT, ') != -1) + f.close() + return ret + +class DFReader_text(DFReader): + '''parse a text dataflash file''' + def __init__(self, filename, zero_time_base=False): + DFReader.__init__(self) + # read the whole file into memory for simplicity + f = open(filename, mode='r') + self.lines = f.readlines() + f.close() + self.formats = { + 'FMT' : DFFormat(0x80, 'FMT', 89, 'BBnNZ', "Type,Length,Name,Format,Columns") + } + self._rewind() + self._zero_time_base = zero_time_base + self.init_clock() + self._rewind() + + def _rewind(self): + '''rewind to start of log''' + DFReader._rewind(self) + self.line = 0 + # find the first valid line + while self.line < len(self.lines): + if self.lines[self.line].startswith("FMT, "): + break + self.line += 1 + + def _parse_next(self): + '''read one message, returning it as an object''' + + this_line = self.line + while self.line < len(self.lines): + s = self.lines[self.line].rstrip() + elements = s.split(", ") + this_line = self.line + # move to next line + self.line += 1 + if len(elements) >= 2: + # this_line is good + break + + if this_line >= len(self.lines): + return None + + # cope with empty structures + if len(elements) == 5 and elements[-1] == ',': + elements[-1] = '' + elements.append('') + + self.percent = 100.0 * (this_line / float(len(self.lines))) + + msg_type = elements[0] + + if not msg_type in self.formats: + return self._parse_next() + + fmt = self.formats[msg_type] + + if len(elements) < len(fmt.format)+1: + # not enough columns + return self._parse_next() + + elements = elements[1:] + + name = fmt.name.rstrip('\0') + if name == 'FMT': + # add to formats + # name, len, format, headings + self.formats[elements[2]] = DFFormat(int(elements[0]), elements[2], int(elements[1]), elements[3], elements[4]) + + try: + m = DFMessage(fmt, elements, False) + except ValueError: + return self._parse_next() + + self._add_msg(m) + + return m + + +if __name__ == "__main__": + import sys + use_profiler = False + if use_profiler: + from line_profiler import LineProfiler + profiler = LineProfiler() + profiler.add_function(DFReader_binary._parse_next) + profiler.add_function(DFReader_binary._add_msg) + profiler.add_function(DFReader._set_time) + profiler.enable_by_count() + + filename = sys.argv[1] + if filename.endswith('.log'): + log = DFReader_text(filename) + else: + log = DFReader_binary(filename) + while True: + m = log.recv_msg() + if m is None: + break + #print(m) + if use_profiler: + profiler.print_stats() + diff --git a/pymavlink/README.txt b/pymavlink/README.txt new file mode 100644 index 0000000..a87f257 --- /dev/null +++ b/pymavlink/README.txt @@ -0,0 +1,9 @@ +This is a python implementation of the MAVLink protocol. + +Please see http://www.qgroundcontrol.org/mavlink/pymavlink for +documentation + +License +------- + +pymavlink is released under the GNU Lesser General Public License v3 or later diff --git a/pymavlink/__init__.py b/pymavlink/__init__.py new file mode 100644 index 0000000..27bfa2b --- /dev/null +++ b/pymavlink/__init__.py @@ -0,0 +1 @@ +'''Python MAVLink library - see http://www.qgroundcontrol.org/mavlink/mavproxy_startpage''' diff --git a/pymavlink/dialects/__init__.py b/pymavlink/dialects/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/pymavlink/dialects/v09/__init__.py b/pymavlink/dialects/v09/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/pymavlink/dialects/v09/ardupilotmega.py b/pymavlink/dialects/v09/ardupilotmega.py new file mode 100644 index 0000000..b87b26d --- /dev/null +++ b/pymavlink/dialects/v09/ardupilotmega.py @@ -0,0 +1,6160 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: ardupilotmega.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "0.9" +DIALECT = "ardupilotmega" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 85, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if False: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at waypoint (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this waypoint an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this waypoint an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this waypoint for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this waypoint for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this waypoint for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this waypoint for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Empty''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system to + # control the vehicle attitude and the + # attitude of various sensors such + # as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Empty''' +enums['MAV_CMD'][176].param[3] = '''Empty''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera capturing. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera capturing.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system + # to control the vehicle attitude and the + # attitude of various + # devices such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + ''') +enums['MAV_CMD'][201].param[1] = '''Region of interest mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple cameras etc.)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch(deg*100) or lat, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll(deg*100) or lon depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw(deg*100) or alt (in cm) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''Empty''' +enums['MAV_CMD'][205].param[5] = '''Empty''' +enums['MAV_CMD'][205].param[6] = '''Empty''' +enums['MAV_CMD'][205].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Empty''' +enums['MAV_CMD'][241].param[6] = '''Empty''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[3] = '''Reserved''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_ENUM_END = 246 # +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# FENCE_ACTION +enums['FENCE_ACTION'] = {} +FENCE_ACTION_NONE = 0 # Disable fenced mode +enums['FENCE_ACTION'][0] = EnumEntry('FENCE_ACTION_NONE', '''Disable fenced mode''') +FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0) +enums['FENCE_ACTION'][1] = EnumEntry('FENCE_ACTION_GUIDED', '''Switched to guided mode to return point (fence point 0)''') +FENCE_ACTION_ENUM_END = 2 # +enums['FENCE_ACTION'][2] = EnumEntry('FENCE_ACTION_ENUM_END', '''''') + +# FENCE_BREACH +enums['FENCE_BREACH'] = {} +FENCE_BREACH_NONE = 0 # No last fence breach +enums['FENCE_BREACH'][0] = EnumEntry('FENCE_BREACH_NONE', '''No last fence breach''') +FENCE_BREACH_MINALT = 1 # Breached minimum altitude +enums['FENCE_BREACH'][1] = EnumEntry('FENCE_BREACH_MINALT', '''Breached minimum altitude''') +FENCE_BREACH_MAXALT = 2 # Breached minimum altitude +enums['FENCE_BREACH'][2] = EnumEntry('FENCE_BREACH_MAXALT', '''Breached minimum altitude''') +FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary +enums['FENCE_BREACH'][3] = EnumEntry('FENCE_BREACH_BOUNDARY', '''Breached fence boundary''') +FENCE_BREACH_ENUM_END = 4 # +enums['FENCE_BREACH'][4] = EnumEntry('FENCE_BREACH_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next waypoint. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next waypoint.''') +MAV_ROI_WPINDEX = 2 # Point toward given waypoint. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given waypoint.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_SENSOR_OFFSETS = 150 +MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151 +MAVLINK_MSG_ID_MEMINFO = 152 +MAVLINK_MSG_ID_AP_ADC = 153 +MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154 +MAVLINK_MSG_ID_DIGICAM_CONTROL = 155 +MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156 +MAVLINK_MSG_ID_MOUNT_CONTROL = 157 +MAVLINK_MSG_ID_MOUNT_STATUS = 158 +MAVLINK_MSG_ID_FENCE_POINT = 160 +MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161 +MAVLINK_MSG_ID_FENCE_STATUS = 162 +MAVLINK_MSG_ID_AHRS = 163 +MAVLINK_MSG_ID_SIMSTATE = 164 +MAVLINK_MSG_ID_HWSTATUS = 165 +MAVLINK_MSG_ID_RADIO = 166 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_BOOT = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 3 +MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_ACTION_ACK = 9 +MAVLINK_MSG_ID_ACTION = 10 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_SET_NAV_MODE = 12 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_GPS_STATUS = 27 +MAVLINK_MSG_ID_RAW_IMU = 28 +MAVLINK_MSG_ID_RAW_PRESSURE = 29 +MAVLINK_MSG_ID_SCALED_PRESSURE = 38 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_LOCAL_POSITION = 31 +MAVLINK_MSG_ID_GLOBAL_POSITION = 33 +MAVLINK_MSG_ID_GPS_RAW = 32 +MAVLINK_MSG_ID_SYS_STATUS = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37 +MAVLINK_MSG_ID_WAYPOINT = 39 +MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40 +MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41 +MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42 +MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43 +MAVLINK_MSG_ID_WAYPOINT_COUNT = 44 +MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45 +MAVLINK_MSG_ID_WAYPOINT_REACHED = 46 +MAVLINK_MSG_ID_WAYPOINT_ACK = 47 +MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51 +MAVLINK_MSG_ID_CONTROL_STATUS = 52 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_POSITION_TARGET = 63 +MAVLINK_MSG_ID_STATE_CORRECTION = 64 +MAVLINK_MSG_ID_SET_ALTITUDE = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_HIL_STATE = 67 +MAVLINK_MSG_ID_HIL_CONTROLS = 68 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND = 75 +MAVLINK_MSG_ID_COMMAND_ACK = 76 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140 +MAVLINK_MSG_ID_DEBUG_VECT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 253 +MAVLINK_MSG_ID_STATUSTEXT = 254 +MAVLINK_MSG_ID_DEBUG = 255 + +class MAVLink_sensor_offsets_message(MAVLink_message): + ''' + Offsets and calibrations values for hardware sensors. + This makes it easier to debug the calibration process. + ''' + id = MAVLINK_MSG_ID_SENSOR_OFFSETS + name = 'SENSOR_OFFSETS' + fieldnames = ['mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z', 'mag_declination', 'raw_press', 'raw_temp', 'gyro_cal_x', 'gyro_cal_y', 'gyro_cal_z', 'accel_cal_x', 'accel_cal_y', 'accel_cal_z'] + ordered_fieldnames = [ 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z', 'mag_declination', 'raw_press', 'raw_temp', 'gyro_cal_x', 'gyro_cal_y', 'gyro_cal_z', 'accel_cal_x', 'accel_cal_y', 'accel_cal_z' ] + format = '>hhhfiiffffff' + native_format = bytearray('>hhhfiiffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 143 + + def __init__(self, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z): + MAVLink_message.__init__(self, MAVLink_sensor_offsets_message.id, MAVLink_sensor_offsets_message.name) + self._fieldnames = MAVLink_sensor_offsets_message.fieldnames + self.mag_ofs_x = mag_ofs_x + self.mag_ofs_y = mag_ofs_y + self.mag_ofs_z = mag_ofs_z + self.mag_declination = mag_declination + self.raw_press = raw_press + self.raw_temp = raw_temp + self.gyro_cal_x = gyro_cal_x + self.gyro_cal_y = gyro_cal_y + self.gyro_cal_z = gyro_cal_z + self.accel_cal_x = accel_cal_x + self.accel_cal_y = accel_cal_y + self.accel_cal_z = accel_cal_z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 143, struct.pack('>hhhfiiffffff', self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z, self.mag_declination, self.raw_press, self.raw_temp, self.gyro_cal_x, self.gyro_cal_y, self.gyro_cal_z, self.accel_cal_x, self.accel_cal_y, self.accel_cal_z)) + +class MAVLink_set_mag_offsets_message(MAVLink_message): + ''' + set the magnetometer offsets + ''' + id = MAVLINK_MSG_ID_SET_MAG_OFFSETS + name = 'SET_MAG_OFFSETS' + fieldnames = ['target_system', 'target_component', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z' ] + format = '>BBhhh' + native_format = bytearray('>BBhhh', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 29 + + def __init__(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z): + MAVLink_message.__init__(self, MAVLink_set_mag_offsets_message.id, MAVLink_set_mag_offsets_message.name) + self._fieldnames = MAVLink_set_mag_offsets_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.mag_ofs_x = mag_ofs_x + self.mag_ofs_y = mag_ofs_y + self.mag_ofs_z = mag_ofs_z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 29, struct.pack('>BBhhh', self.target_system, self.target_component, self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z)) + +class MAVLink_meminfo_message(MAVLink_message): + ''' + state of APM memory + ''' + id = MAVLINK_MSG_ID_MEMINFO + name = 'MEMINFO' + fieldnames = ['brkval', 'freemem'] + ordered_fieldnames = [ 'brkval', 'freemem' ] + format = '>HH' + native_format = bytearray('>HH', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 208 + + def __init__(self, brkval, freemem): + MAVLink_message.__init__(self, MAVLink_meminfo_message.id, MAVLink_meminfo_message.name) + self._fieldnames = MAVLink_meminfo_message.fieldnames + self.brkval = brkval + self.freemem = freemem + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 208, struct.pack('>HH', self.brkval, self.freemem)) + +class MAVLink_ap_adc_message(MAVLink_message): + ''' + raw ADC output + ''' + id = MAVLINK_MSG_ID_AP_ADC + name = 'AP_ADC' + fieldnames = ['adc1', 'adc2', 'adc3', 'adc4', 'adc5', 'adc6'] + ordered_fieldnames = [ 'adc1', 'adc2', 'adc3', 'adc4', 'adc5', 'adc6' ] + format = '>HHHHHH' + native_format = bytearray('>HHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 188 + + def __init__(self, adc1, adc2, adc3, adc4, adc5, adc6): + MAVLink_message.__init__(self, MAVLink_ap_adc_message.id, MAVLink_ap_adc_message.name) + self._fieldnames = MAVLink_ap_adc_message.fieldnames + self.adc1 = adc1 + self.adc2 = adc2 + self.adc3 = adc3 + self.adc4 = adc4 + self.adc5 = adc5 + self.adc6 = adc6 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 188, struct.pack('>HHHHHH', self.adc1, self.adc2, self.adc3, self.adc4, self.adc5, self.adc6)) + +class MAVLink_digicam_configure_message(MAVLink_message): + ''' + Configure on-board Camera Control System. + ''' + id = MAVLINK_MSG_ID_DIGICAM_CONFIGURE + name = 'DIGICAM_CONFIGURE' + fieldnames = ['target_system', 'target_component', 'mode', 'shutter_speed', 'aperture', 'iso', 'exposure_type', 'command_id', 'engine_cut_off', 'extra_param', 'extra_value'] + ordered_fieldnames = [ 'target_system', 'target_component', 'mode', 'shutter_speed', 'aperture', 'iso', 'exposure_type', 'command_id', 'engine_cut_off', 'extra_param', 'extra_value' ] + format = '>BBBHBBBBBBf' + native_format = bytearray('>BBBHBBBBBBf', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 118 + + def __init__(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value): + MAVLink_message.__init__(self, MAVLink_digicam_configure_message.id, MAVLink_digicam_configure_message.name) + self._fieldnames = MAVLink_digicam_configure_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.mode = mode + self.shutter_speed = shutter_speed + self.aperture = aperture + self.iso = iso + self.exposure_type = exposure_type + self.command_id = command_id + self.engine_cut_off = engine_cut_off + self.extra_param = extra_param + self.extra_value = extra_value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 118, struct.pack('>BBBHBBBBBBf', self.target_system, self.target_component, self.mode, self.shutter_speed, self.aperture, self.iso, self.exposure_type, self.command_id, self.engine_cut_off, self.extra_param, self.extra_value)) + +class MAVLink_digicam_control_message(MAVLink_message): + ''' + Control on-board Camera Control System to take shots. + ''' + id = MAVLINK_MSG_ID_DIGICAM_CONTROL + name = 'DIGICAM_CONTROL' + fieldnames = ['target_system', 'target_component', 'session', 'zoom_pos', 'zoom_step', 'focus_lock', 'shot', 'command_id', 'extra_param', 'extra_value'] + ordered_fieldnames = [ 'target_system', 'target_component', 'session', 'zoom_pos', 'zoom_step', 'focus_lock', 'shot', 'command_id', 'extra_param', 'extra_value' ] + format = '>BBBBbBBBBf' + native_format = bytearray('>BBBBbBBBBf', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 242 + + def __init__(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value): + MAVLink_message.__init__(self, MAVLink_digicam_control_message.id, MAVLink_digicam_control_message.name) + self._fieldnames = MAVLink_digicam_control_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.session = session + self.zoom_pos = zoom_pos + self.zoom_step = zoom_step + self.focus_lock = focus_lock + self.shot = shot + self.command_id = command_id + self.extra_param = extra_param + self.extra_value = extra_value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 242, struct.pack('>BBBBbBBBBf', self.target_system, self.target_component, self.session, self.zoom_pos, self.zoom_step, self.focus_lock, self.shot, self.command_id, self.extra_param, self.extra_value)) + +class MAVLink_mount_configure_message(MAVLink_message): + ''' + Message to configure a camera mount, directional antenna, etc. + ''' + id = MAVLINK_MSG_ID_MOUNT_CONFIGURE + name = 'MOUNT_CONFIGURE' + fieldnames = ['target_system', 'target_component', 'mount_mode', 'stab_roll', 'stab_pitch', 'stab_yaw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'mount_mode', 'stab_roll', 'stab_pitch', 'stab_yaw' ] + format = '>BBBBBB' + native_format = bytearray('>BBBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 19 + + def __init__(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw): + MAVLink_message.__init__(self, MAVLink_mount_configure_message.id, MAVLink_mount_configure_message.name) + self._fieldnames = MAVLink_mount_configure_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.mount_mode = mount_mode + self.stab_roll = stab_roll + self.stab_pitch = stab_pitch + self.stab_yaw = stab_yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 19, struct.pack('>BBBBBB', self.target_system, self.target_component, self.mount_mode, self.stab_roll, self.stab_pitch, self.stab_yaw)) + +class MAVLink_mount_control_message(MAVLink_message): + ''' + Message to control a camera mount, directional antenna, etc. + ''' + id = MAVLINK_MSG_ID_MOUNT_CONTROL + name = 'MOUNT_CONTROL' + fieldnames = ['target_system', 'target_component', 'input_a', 'input_b', 'input_c', 'save_position'] + ordered_fieldnames = [ 'target_system', 'target_component', 'input_a', 'input_b', 'input_c', 'save_position' ] + format = '>BBiiiB' + native_format = bytearray('>BBiiiB', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 97 + + def __init__(self, target_system, target_component, input_a, input_b, input_c, save_position): + MAVLink_message.__init__(self, MAVLink_mount_control_message.id, MAVLink_mount_control_message.name) + self._fieldnames = MAVLink_mount_control_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.input_a = input_a + self.input_b = input_b + self.input_c = input_c + self.save_position = save_position + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 97, struct.pack('>BBiiiB', self.target_system, self.target_component, self.input_a, self.input_b, self.input_c, self.save_position)) + +class MAVLink_mount_status_message(MAVLink_message): + ''' + Message with some status from APM to GCS about camera or + antenna mount + ''' + id = MAVLINK_MSG_ID_MOUNT_STATUS + name = 'MOUNT_STATUS' + fieldnames = ['target_system', 'target_component', 'pointing_a', 'pointing_b', 'pointing_c'] + ordered_fieldnames = [ 'target_system', 'target_component', 'pointing_a', 'pointing_b', 'pointing_c' ] + format = '>BBiii' + native_format = bytearray('>BBiii', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 233 + + def __init__(self, target_system, target_component, pointing_a, pointing_b, pointing_c): + MAVLink_message.__init__(self, MAVLink_mount_status_message.id, MAVLink_mount_status_message.name) + self._fieldnames = MAVLink_mount_status_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.pointing_a = pointing_a + self.pointing_b = pointing_b + self.pointing_c = pointing_c + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 233, struct.pack('>BBiii', self.target_system, self.target_component, self.pointing_a, self.pointing_b, self.pointing_c)) + +class MAVLink_fence_point_message(MAVLink_message): + ''' + A fence point. Used to set a point when from GCS + -> MAV. Also used to return a point from MAV -> GCS + ''' + id = MAVLINK_MSG_ID_FENCE_POINT + name = 'FENCE_POINT' + fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng'] + ordered_fieldnames = [ 'target_system', 'target_component', 'idx', 'count', 'lat', 'lng' ] + format = '>BBBBff' + native_format = bytearray('>BBBBff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 18 + + def __init__(self, target_system, target_component, idx, count, lat, lng): + MAVLink_message.__init__(self, MAVLink_fence_point_message.id, MAVLink_fence_point_message.name) + self._fieldnames = MAVLink_fence_point_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.idx = idx + self.count = count + self.lat = lat + self.lng = lng + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 18, struct.pack('>BBBBff', self.target_system, self.target_component, self.idx, self.count, self.lat, self.lng)) + +class MAVLink_fence_fetch_point_message(MAVLink_message): + ''' + Request a current fence point from MAV + ''' + id = MAVLINK_MSG_ID_FENCE_FETCH_POINT + name = 'FENCE_FETCH_POINT' + fieldnames = ['target_system', 'target_component', 'idx'] + ordered_fieldnames = [ 'target_system', 'target_component', 'idx' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 68 + + def __init__(self, target_system, target_component, idx): + MAVLink_message.__init__(self, MAVLink_fence_fetch_point_message.id, MAVLink_fence_fetch_point_message.name) + self._fieldnames = MAVLink_fence_fetch_point_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.idx = idx + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 68, struct.pack('>BBB', self.target_system, self.target_component, self.idx)) + +class MAVLink_fence_status_message(MAVLink_message): + ''' + Status of geo-fencing. Sent in extended status + stream when fencing enabled + ''' + id = MAVLINK_MSG_ID_FENCE_STATUS + name = 'FENCE_STATUS' + fieldnames = ['breach_status', 'breach_count', 'breach_type', 'breach_time'] + ordered_fieldnames = [ 'breach_status', 'breach_count', 'breach_type', 'breach_time' ] + format = '>BHBI' + native_format = bytearray('>BHBI', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 136 + + def __init__(self, breach_status, breach_count, breach_type, breach_time): + MAVLink_message.__init__(self, MAVLink_fence_status_message.id, MAVLink_fence_status_message.name) + self._fieldnames = MAVLink_fence_status_message.fieldnames + self.breach_status = breach_status + self.breach_count = breach_count + self.breach_type = breach_type + self.breach_time = breach_time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 136, struct.pack('>BHBI', self.breach_status, self.breach_count, self.breach_type, self.breach_time)) + +class MAVLink_ahrs_message(MAVLink_message): + ''' + Status of DCM attitude estimator + ''' + id = MAVLINK_MSG_ID_AHRS + name = 'AHRS' + fieldnames = ['omegaIx', 'omegaIy', 'omegaIz', 'accel_weight', 'renorm_val', 'error_rp', 'error_yaw'] + ordered_fieldnames = [ 'omegaIx', 'omegaIy', 'omegaIz', 'accel_weight', 'renorm_val', 'error_rp', 'error_yaw' ] + format = '>fffffff' + native_format = bytearray('>fffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 127 + + def __init__(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): + MAVLink_message.__init__(self, MAVLink_ahrs_message.id, MAVLink_ahrs_message.name) + self._fieldnames = MAVLink_ahrs_message.fieldnames + self.omegaIx = omegaIx + self.omegaIy = omegaIy + self.omegaIz = omegaIz + self.accel_weight = accel_weight + self.renorm_val = renorm_val + self.error_rp = error_rp + self.error_yaw = error_yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 127, struct.pack('>fffffff', self.omegaIx, self.omegaIy, self.omegaIz, self.accel_weight, self.renorm_val, self.error_rp, self.error_yaw)) + +class MAVLink_simstate_message(MAVLink_message): + ''' + Status of simulation environment, if used + ''' + id = MAVLINK_MSG_ID_SIMSTATE + name = 'SIMSTATE' + fieldnames = ['roll', 'pitch', 'yaw', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro'] + ordered_fieldnames = [ 'roll', 'pitch', 'yaw', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro' ] + format = '>fffffffff' + native_format = bytearray('>fffffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 42 + + def __init__(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): + MAVLink_message.__init__(self, MAVLink_simstate_message.id, MAVLink_simstate_message.name) + self._fieldnames = MAVLink_simstate_message.fieldnames + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 42, struct.pack('>fffffffff', self.roll, self.pitch, self.yaw, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro)) + +class MAVLink_hwstatus_message(MAVLink_message): + ''' + Status of key hardware + ''' + id = MAVLINK_MSG_ID_HWSTATUS + name = 'HWSTATUS' + fieldnames = ['Vcc', 'I2Cerr'] + ordered_fieldnames = [ 'Vcc', 'I2Cerr' ] + format = '>HB' + native_format = bytearray('>HB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 21 + + def __init__(self, Vcc, I2Cerr): + MAVLink_message.__init__(self, MAVLink_hwstatus_message.id, MAVLink_hwstatus_message.name) + self._fieldnames = MAVLink_hwstatus_message.fieldnames + self.Vcc = Vcc + self.I2Cerr = I2Cerr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 21, struct.pack('>HB', self.Vcc, self.I2Cerr)) + +class MAVLink_radio_message(MAVLink_message): + ''' + Status generated by radio + ''' + id = MAVLINK_MSG_ID_RADIO + name = 'RADIO' + fieldnames = ['rssi', 'remrssi', 'txbuf', 'noise', 'remnoise', 'rxerrors', 'fixed'] + ordered_fieldnames = [ 'rssi', 'remrssi', 'txbuf', 'noise', 'remnoise', 'rxerrors', 'fixed' ] + format = '>BBBBBHH' + native_format = bytearray('>BBBBBHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 93 + + def __init__(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + MAVLink_message.__init__(self, MAVLink_radio_message.id, MAVLink_radio_message.name) + self._fieldnames = MAVLink_radio_message.fieldnames + self.rssi = rssi + self.remrssi = remrssi + self.txbuf = txbuf + self.noise = noise + self.remnoise = remnoise + self.rxerrors = rxerrors + self.fixed = fixed + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 93, struct.pack('>BBBBBHH', self.rssi, self.remrssi, self.txbuf, self.noise, self.remnoise, self.rxerrors, self.fixed)) + +class MAVLink_heartbeat_message(MAVLink_message): + ''' + The heartbeat message shows that a system is present and + responding. The type of the MAV and Autopilot hardware allow + the receiving system to treat further messages from this + system appropriate (e.g. by laying out the user interface + based on the autopilot). + ''' + id = MAVLINK_MSG_ID_HEARTBEAT + name = 'HEARTBEAT' + fieldnames = ['type', 'autopilot', 'mavlink_version'] + ordered_fieldnames = [ 'type', 'autopilot', 'mavlink_version' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 72 + + def __init__(self, type, autopilot, mavlink_version): + MAVLink_message.__init__(self, MAVLink_heartbeat_message.id, MAVLink_heartbeat_message.name) + self._fieldnames = MAVLink_heartbeat_message.fieldnames + self.type = type + self.autopilot = autopilot + self.mavlink_version = mavlink_version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) + +class MAVLink_boot_message(MAVLink_message): + ''' + The boot message indicates that a system is starting. The + onboard software version allows to keep track of onboard + soft/firmware revisions. + ''' + id = MAVLINK_MSG_ID_BOOT + name = 'BOOT' + fieldnames = ['version'] + ordered_fieldnames = [ 'version' ] + format = '>I' + native_format = bytearray('>I', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 39 + + def __init__(self, version): + MAVLink_message.__init__(self, MAVLink_boot_message.id, MAVLink_boot_message.name) + self._fieldnames = MAVLink_boot_message.fieldnames + self.version = version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version)) + +class MAVLink_system_time_message(MAVLink_message): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME + name = 'SYSTEM_TIME' + fieldnames = ['time_usec'] + ordered_fieldnames = [ 'time_usec' ] + format = '>Q' + native_format = bytearray('>Q', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 190 + + def __init__(self, time_usec): + MAVLink_message.__init__(self, MAVLink_system_time_message.id, MAVLink_system_time_message.name) + self._fieldnames = MAVLink_system_time_message.fieldnames + self.time_usec = time_usec + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec)) + +class MAVLink_ping_message(MAVLink_message): + ''' + A ping message either requesting or responding to a ping. This + allows to measure the system latencies, including serial port, + radio modem and UDP connections. + ''' + id = MAVLINK_MSG_ID_PING + name = 'PING' + fieldnames = ['seq', 'target_system', 'target_component', 'time'] + ordered_fieldnames = [ 'seq', 'target_system', 'target_component', 'time' ] + format = '>IBBQ' + native_format = bytearray('>IBBQ', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 92 + + def __init__(self, seq, target_system, target_component, time): + MAVLink_message.__init__(self, MAVLink_ping_message.id, MAVLink_ping_message.name) + self._fieldnames = MAVLink_ping_message.fieldnames + self.seq = seq + self.target_system = target_system + self.target_component = target_component + self.time = time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time)) + +class MAVLink_system_time_utc_message(MAVLink_message): + ''' + UTC date and time from GPS module + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME_UTC + name = 'SYSTEM_TIME_UTC' + fieldnames = ['utc_date', 'utc_time'] + ordered_fieldnames = [ 'utc_date', 'utc_time' ] + format = '>II' + native_format = bytearray('>II', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 191 + + def __init__(self, utc_date, utc_time): + MAVLink_message.__init__(self, MAVLink_system_time_utc_message.id, MAVLink_system_time_utc_message.name) + self._fieldnames = MAVLink_system_time_utc_message.fieldnames + self.utc_date = utc_date + self.utc_time = utc_time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time)) + +class MAVLink_change_operator_control_message(MAVLink_message): + ''' + Request to control this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL + name = 'CHANGE_OPERATOR_CONTROL' + fieldnames = ['target_system', 'control_request', 'version', 'passkey'] + ordered_fieldnames = [ 'target_system', 'control_request', 'version', 'passkey' ] + format = '>BBB25s' + native_format = bytearray('>BBBc', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 25] + crc_extra = 217 + + def __init__(self, target_system, control_request, version, passkey): + MAVLink_message.__init__(self, MAVLink_change_operator_control_message.id, MAVLink_change_operator_control_message.name) + self._fieldnames = MAVLink_change_operator_control_message.fieldnames + self.target_system = target_system + self.control_request = control_request + self.version = version + self.passkey = passkey + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey)) + +class MAVLink_change_operator_control_ack_message(MAVLink_message): + ''' + Accept / deny control of this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK + name = 'CHANGE_OPERATOR_CONTROL_ACK' + fieldnames = ['gcs_system_id', 'control_request', 'ack'] + ordered_fieldnames = [ 'gcs_system_id', 'control_request', 'ack' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 104 + + def __init__(self, gcs_system_id, control_request, ack): + MAVLink_message.__init__(self, MAVLink_change_operator_control_ack_message.id, MAVLink_change_operator_control_ack_message.name) + self._fieldnames = MAVLink_change_operator_control_ack_message.fieldnames + self.gcs_system_id = gcs_system_id + self.control_request = control_request + self.ack = ack + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack)) + +class MAVLink_auth_key_message(MAVLink_message): + ''' + Emit an encrypted signature / key identifying this system. + PLEASE NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for true + safety. + ''' + id = MAVLINK_MSG_ID_AUTH_KEY + name = 'AUTH_KEY' + fieldnames = ['key'] + ordered_fieldnames = [ 'key' ] + format = '>32s' + native_format = bytearray('>c', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [32] + crc_extra = 119 + + def __init__(self, key): + MAVLink_message.__init__(self, MAVLink_auth_key_message.id, MAVLink_auth_key_message.name) + self._fieldnames = MAVLink_auth_key_message.fieldnames + self.key = key + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key)) + +class MAVLink_action_ack_message(MAVLink_message): + ''' + This message acknowledges an action. IMPORTANT: The + acknowledgement can be also negative, e.g. the MAV rejects a + reset message because it is in-flight. The action ids are + defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION_ACK + name = 'ACTION_ACK' + fieldnames = ['action', 'result'] + ordered_fieldnames = [ 'action', 'result' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 219 + + def __init__(self, action, result): + MAVLink_message.__init__(self, MAVLink_action_ack_message.id, MAVLink_action_ack_message.name) + self._fieldnames = MAVLink_action_ack_message.fieldnames + self.action = action + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result)) + +class MAVLink_action_message(MAVLink_message): + ''' + An action message allows to execute a certain onboard action. + These include liftoff, land, storing parameters too EEPROM, + shutddown, etc. The action ids are defined in ENUM MAV_ACTION + in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION + name = 'ACTION' + fieldnames = ['target', 'target_component', 'action'] + ordered_fieldnames = [ 'target', 'target_component', 'action' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 60 + + def __init__(self, target, target_component, action): + MAVLink_message.__init__(self, MAVLink_action_message.id, MAVLink_action_message.name) + self._fieldnames = MAVLink_action_message.fieldnames + self.target = target + self.target_component = target_component + self.action = action + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action)) + +class MAVLink_set_mode_message(MAVLink_message): + ''' + Set the system mode, as defined by enum MAV_MODE in + mavlink/include/mavlink_types.h. There is no target component + id as the mode is by definition for the overall aircraft, not + only for one component. + ''' + id = MAVLINK_MSG_ID_SET_MODE + name = 'SET_MODE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 186 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_mode_message.id, MAVLink_set_mode_message.name) + self._fieldnames = MAVLink_set_mode_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode)) + +class MAVLink_set_nav_mode_message(MAVLink_message): + ''' + Set the system navigation mode, as defined by enum + MAV_NAV_MODE in mavlink/include/mavlink_types.h. The + navigation mode applies to the whole aircraft and thus all + components. + ''' + id = MAVLINK_MSG_ID_SET_NAV_MODE + name = 'SET_NAV_MODE' + fieldnames = ['target', 'nav_mode'] + ordered_fieldnames = [ 'target', 'nav_mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 10 + + def __init__(self, target, nav_mode): + MAVLink_message.__init__(self, MAVLink_set_nav_mode_message.id, MAVLink_set_nav_mode_message.name) + self._fieldnames = MAVLink_set_nav_mode_message.fieldnames + self.target = target + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode)) + +class MAVLink_param_request_read_message(MAVLink_message): + ''' + Request to read the onboard parameter with the param_id string + id. Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_index' ] + format = '>BB15bh' + native_format = bytearray('>BBbh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 89 + + def __init__(self, target_system, target_component, param_id, param_index): + MAVLink_message.__init__(self, MAVLink_param_request_read_message.id, MAVLink_param_request_read_message.name) + self._fieldnames = MAVLink_param_request_read_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15bh', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_index)) + +class MAVLink_param_request_list_message(MAVLink_message): + ''' + Request all parameters of this component. After his request, + all parameters are emitted. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_LIST + name = 'PARAM_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 159 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_param_request_list_message.id, MAVLink_param_request_list_message.name) + self._fieldnames = MAVLink_param_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_param_value_message(MAVLink_message): + ''' + Emit the value of a onboard parameter. The inclusion of + param_count and param_index in the message allows the + recipient to keep track of received parameters and allows him + to re-request missing parameters after a loss or timeout. + ''' + id = MAVLINK_MSG_ID_PARAM_VALUE + name = 'PARAM_VALUE' + fieldnames = ['param_id', 'param_value', 'param_count', 'param_index'] + ordered_fieldnames = [ 'param_id', 'param_value', 'param_count', 'param_index' ] + format = '>15bfHH' + native_format = bytearray('>bfHH', 'ascii') + orders = [0, 1, 2, 3] + lengths = [15, 1, 1, 1] + array_lengths = [15, 0, 0, 0] + crc_extra = 162 + + def __init__(self, param_id, param_value, param_count, param_index): + MAVLink_message.__init__(self, MAVLink_param_value_message.id, MAVLink_param_value_message.name) + self._fieldnames = MAVLink_param_value_message.fieldnames + self.param_id = param_id + self.param_value = param_value + self.param_count = param_count + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>15bfHH', self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value, self.param_count, self.param_index)) + +class MAVLink_param_set_message(MAVLink_message): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to + default on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents + to EEPROM. IMPORTANT: The receiving component should + acknowledge the new parameter value by sending a param_value + message to all communication partners. This will also ensure + that multiple GCS all have an up-to-date list of all + parameters. If the sending GCS did not receive a PARAM_VALUE + message within its timeout time, it should re-send the + PARAM_SET message. + ''' + id = MAVLINK_MSG_ID_PARAM_SET + name = 'PARAM_SET' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_value'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_value' ] + format = '>BB15bf' + native_format = bytearray('>BBbf', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 121 + + def __init__(self, target_system, target_component, param_id, param_value): + MAVLink_message.__init__(self, MAVLink_param_set_message.id, MAVLink_param_set_message.name) + self._fieldnames = MAVLink_param_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_value = param_value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15bf', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value)) + +class MAVLink_gps_raw_int_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW_INT + name = 'GPS_RAW_INT' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBiiiffff' + native_format = bytearray('>QBiiiffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 149 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_int_message.id, MAVLink_gps_raw_int_message.name) + self._fieldnames = MAVLink_gps_raw_int_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_scaled_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should contain the scaled values to the described + units + ''' + id = MAVLINK_MSG_ID_SCALED_IMU + name = 'SCALED_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 222 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_scaled_imu_message.id, MAVLink_scaled_imu_message.name) + self._fieldnames = MAVLink_scaled_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_gps_status_message(MAVLink_message): + ''' + The positioning status, as reported by GPS. This message is + intended to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION for the + global position estimate. This message can contain information + for up to 20 satellites. + ''' + id = MAVLINK_MSG_ID_GPS_STATUS + name = 'GPS_STATUS' + fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr'] + ordered_fieldnames = [ 'satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr' ] + format = '>B20b20b20b20b20b' + native_format = bytearray('>Bbbbbb', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 20, 20, 20, 20, 20] + array_lengths = [0, 20, 20, 20, 20, 20] + crc_extra = 110 + + def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + MAVLink_message.__init__(self, MAVLink_gps_status_message.id, MAVLink_gps_status_message.name) + self._fieldnames = MAVLink_gps_status_message.fieldnames + self.satellites_visible = satellites_visible + self.satellite_prn = satellite_prn + self.satellite_used = satellite_used + self.satellite_elevation = satellite_elevation + self.satellite_azimuth = satellite_azimuth + self.satellite_snr = satellite_snr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 110, struct.pack('>B20b20b20b20b20b', self.satellites_visible, self.satellite_prn[0], self.satellite_prn[1], self.satellite_prn[2], self.satellite_prn[3], self.satellite_prn[4], self.satellite_prn[5], self.satellite_prn[6], self.satellite_prn[7], self.satellite_prn[8], self.satellite_prn[9], self.satellite_prn[10], self.satellite_prn[11], self.satellite_prn[12], self.satellite_prn[13], self.satellite_prn[14], self.satellite_prn[15], self.satellite_prn[16], self.satellite_prn[17], self.satellite_prn[18], self.satellite_prn[19], self.satellite_used[0], self.satellite_used[1], self.satellite_used[2], self.satellite_used[3], self.satellite_used[4], self.satellite_used[5], self.satellite_used[6], self.satellite_used[7], self.satellite_used[8], self.satellite_used[9], self.satellite_used[10], self.satellite_used[11], self.satellite_used[12], self.satellite_used[13], self.satellite_used[14], self.satellite_used[15], self.satellite_used[16], self.satellite_used[17], self.satellite_used[18], self.satellite_used[19], self.satellite_elevation[0], self.satellite_elevation[1], self.satellite_elevation[2], self.satellite_elevation[3], self.satellite_elevation[4], self.satellite_elevation[5], self.satellite_elevation[6], self.satellite_elevation[7], self.satellite_elevation[8], self.satellite_elevation[9], self.satellite_elevation[10], self.satellite_elevation[11], self.satellite_elevation[12], self.satellite_elevation[13], self.satellite_elevation[14], self.satellite_elevation[15], self.satellite_elevation[16], self.satellite_elevation[17], self.satellite_elevation[18], self.satellite_elevation[19], self.satellite_azimuth[0], self.satellite_azimuth[1], self.satellite_azimuth[2], self.satellite_azimuth[3], self.satellite_azimuth[4], self.satellite_azimuth[5], self.satellite_azimuth[6], self.satellite_azimuth[7], self.satellite_azimuth[8], self.satellite_azimuth[9], self.satellite_azimuth[10], self.satellite_azimuth[11], self.satellite_azimuth[12], self.satellite_azimuth[13], self.satellite_azimuth[14], self.satellite_azimuth[15], self.satellite_azimuth[16], self.satellite_azimuth[17], self.satellite_azimuth[18], self.satellite_azimuth[19], self.satellite_snr[0], self.satellite_snr[1], self.satellite_snr[2], self.satellite_snr[3], self.satellite_snr[4], self.satellite_snr[5], self.satellite_snr[6], self.satellite_snr[7], self.satellite_snr[8], self.satellite_snr[9], self.satellite_snr[10], self.satellite_snr[11], self.satellite_snr[12], self.satellite_snr[13], self.satellite_snr[14], self.satellite_snr[15], self.satellite_snr[16], self.satellite_snr[17], self.satellite_snr[18], self.satellite_snr[19])) + +class MAVLink_raw_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should always contain the true raw values without any + scaling to allow data capture and system debugging. + ''' + id = MAVLINK_MSG_ID_RAW_IMU + name = 'RAW_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 179 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_raw_imu_message.id, MAVLink_raw_imu_message.name) + self._fieldnames = MAVLink_raw_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_raw_pressure_message(MAVLink_message): + ''' + The RAW pressure readings for the typical setup of one + absolute pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + ''' + id = MAVLINK_MSG_ID_RAW_PRESSURE + name = 'RAW_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature' ] + format = '>Qhhhh' + native_format = bytearray('>Qhhhh', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 136 + + def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature): + MAVLink_message.__init__(self, MAVLink_raw_pressure_message.id, MAVLink_raw_pressure_message.name) + self._fieldnames = MAVLink_raw_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff1 = press_diff1 + self.press_diff2 = press_diff2 + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature)) + +class MAVLink_scaled_pressure_message(MAVLink_message): + ''' + The pressure readings for the typical setup of one absolute + and differential pressure sensor. The units are as specified + in each field. + ''' + id = MAVLINK_MSG_ID_SCALED_PRESSURE + name = 'SCALED_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff', 'temperature' ] + format = '>Qffh' + native_format = bytearray('>Qffh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 229 + + def __init__(self, usec, press_abs, press_diff, temperature): + MAVLink_message.__init__(self, MAVLink_scaled_pressure_message.id, MAVLink_scaled_pressure_message.name) + self._fieldnames = MAVLink_scaled_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff = press_diff + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature)) + +class MAVLink_attitude_message(MAVLink_message): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, + X-front, Y-right). + ''' + id = MAVLINK_MSG_ID_ATTITUDE + name = 'ATTITUDE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 66 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + MAVLink_message.__init__(self, MAVLink_attitude_message.id, MAVLink_attitude_message.name) + self._fieldnames = MAVLink_attitude_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed)) + +class MAVLink_local_position_message(MAVLink_message): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, Z-axis down + (aeronautical frame) + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION + name = 'LOCAL_POSITION' + fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'x', 'y', 'z', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, usec, x, y, z, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_local_position_message.id, MAVLink_local_position_message.name) + self._fieldnames = MAVLink_local_position_message.fieldnames + self.usec = usec + self.x = x + self.y = y + self.z = z + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz)) + +class MAVLink_global_position_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). Coordinate frame is right-handed, Z-axis up + (GPS frame) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION + name = 'GLOBAL_POSITION' + fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 147 + + def __init__(self, usec, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_message.id, MAVLink_global_position_message.name) + self._fieldnames = MAVLink_global_position_message.fieldnames + self.usec = usec + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_gps_raw_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW + name = 'GPS_RAW' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBfffffff' + native_format = bytearray('>QBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 185 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_message.id, MAVLink_gps_raw_message.name) + self._fieldnames = MAVLink_gps_raw_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_sys_status_message(MAVLink_message): + ''' + The general system state. If the system is following the + MAVLink standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is either + LOCKED (motors shut down and locked), MANUAL (system under RC + control), GUIDED (system with autonomous position control, + position setpoint controlled manually) or AUTO (system guided + by path/waypoint planner). The NAV_MODE defined the current + flight state: LIFTOFF (often an open-loop maneuver), LANDING, + WAYPOINTS or VECTOR. This represents the internal navigation + state machine. The system status shows wether the system is + currently active or not and if an emergency occured. During + the CRITICAL and EMERGENCY states the MAV is still considered + to be active, but should start emergency procedures + autonomously. After a failure occured it should first move + from active to critical to allow manual intervention and then + move to emergency after a certain timeout. + ''' + id = MAVLINK_MSG_ID_SYS_STATUS + name = 'SYS_STATUS' + fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop'] + ordered_fieldnames = [ 'mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop' ] + format = '>BBBHHHH' + native_format = bytearray('>BBBHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 112 + + def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + MAVLink_message.__init__(self, MAVLink_sys_status_message.id, MAVLink_sys_status_message.name) + self._fieldnames = MAVLink_sys_status_message.fieldnames + self.mode = mode + self.nav_mode = nav_mode + self.status = status + self.load = load + self.vbat = vbat + self.battery_remaining = battery_remaining + self.packet_drop = packet_drop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop)) + +class MAVLink_rc_channels_raw_message(MAVLink_message): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_RAW + name = 'RC_CHANNELS_RAW' + fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi'] + ordered_fieldnames = [ 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi' ] + format = '>HHHHHHHHB' + native_format = bytearray('>HHHHHHHHB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 252 + + def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_raw_message.id, MAVLink_rc_channels_raw_message.name) + self._fieldnames = MAVLink_rc_channels_raw_message.fieldnames + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi)) + +class MAVLink_rc_channels_scaled_message(MAVLink_message): + ''' + The scaled values of the RC channels received. (-100%) -10000, + (0%) 0, (100%) 10000 + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_SCALED + name = 'RC_CHANNELS_SCALED' + fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi'] + ordered_fieldnames = [ 'chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi' ] + format = '>hhhhhhhhB' + native_format = bytearray('>hhhhhhhhB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 162 + + def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_scaled_message.id, MAVLink_rc_channels_scaled_message.name) + self._fieldnames = MAVLink_rc_channels_scaled_message.fieldnames + self.chan1_scaled = chan1_scaled + self.chan2_scaled = chan2_scaled + self.chan3_scaled = chan3_scaled + self.chan4_scaled = chan4_scaled + self.chan5_scaled = chan5_scaled + self.chan6_scaled = chan6_scaled + self.chan7_scaled = chan7_scaled + self.chan8_scaled = chan8_scaled + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi)) + +class MAVLink_servo_output_raw_message(MAVLink_message): + ''' + The RAW values of the servo outputs (for RC input from the + remote, use the RC_CHANNELS messages). The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + ''' + id = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW + name = 'SERVO_OUTPUT_RAW' + fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw'] + ordered_fieldnames = [ 'servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw' ] + format = '>HHHHHHHH' + native_format = bytearray('>HHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + MAVLink_message.__init__(self, MAVLink_servo_output_raw_message.id, MAVLink_servo_output_raw_message.name) + self._fieldnames = MAVLink_servo_output_raw_message.fieldnames + self.servo1_raw = servo1_raw + self.servo2_raw = servo2_raw + self.servo3_raw = servo3_raw + self.servo4_raw = servo4_raw + self.servo5_raw = servo5_raw + self.servo6_raw = servo6_raw + self.servo7_raw = servo7_raw + self.servo8_raw = servo8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw)) + +class MAVLink_waypoint_message(MAVLink_message): + ''' + Message encoding a waypoint. This message is emitted to + announce the presence of a waypoint and to set a waypoint + on the system. The waypoint can be either in x, y, z meters + (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is + Z-down, right handed, global frame is Z-up, right handed + ''' + id = MAVLINK_MSG_ID_WAYPOINT + name = 'WAYPOINT' + fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z' ] + format = '>BBHBBBBfffffff' + native_format = bytearray('>BBHBBBBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 128 + + def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + MAVLink_message.__init__(self, MAVLink_waypoint_message.id, MAVLink_waypoint_message.name) + self._fieldnames = MAVLink_waypoint_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + self.frame = frame + self.command = command + self.current = current + self.autocontinue = autocontinue + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z)) + +class MAVLink_waypoint_request_message(MAVLink_message): + ''' + Request the information of the waypoint with the sequence + number seq. The response of the system to this message should + be a WAYPOINT message. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST + name = 'WAYPOINT_REQUEST' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 9 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_request_message.id, MAVLink_waypoint_request_message.name) + self._fieldnames = MAVLink_waypoint_request_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_set_current_message(MAVLink_message): + ''' + Set the waypoint with sequence number seq as current waypoint. + This means that the MAV will continue to this waypoint on the + shortest path (not following the waypoints in-between). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT + name = 'WAYPOINT_SET_CURRENT' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 106 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_set_current_message.id, MAVLink_waypoint_set_current_message.name) + self._fieldnames = MAVLink_waypoint_set_current_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_current_message(MAVLink_message): + ''' + Message that announces the sequence number of the current + active waypoint. The MAV will fly towards this waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CURRENT + name = 'WAYPOINT_CURRENT' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 101 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_current_message.id, MAVLink_waypoint_current_message.name) + self._fieldnames = MAVLink_waypoint_current_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_request_list_message(MAVLink_message): + ''' + Request the overall list of waypoints from the + system/component. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST + name = 'WAYPOINT_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_request_list_message.id, MAVLink_waypoint_request_list_message.name) + self._fieldnames = MAVLink_waypoint_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_count_message(MAVLink_message): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST + by the MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of waypoints. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_COUNT + name = 'WAYPOINT_COUNT' + fieldnames = ['target_system', 'target_component', 'count'] + ordered_fieldnames = [ 'target_system', 'target_component', 'count' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 4 + + def __init__(self, target_system, target_component, count): + MAVLink_message.__init__(self, MAVLink_waypoint_count_message.id, MAVLink_waypoint_count_message.name) + self._fieldnames = MAVLink_waypoint_count_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.count = count + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count)) + +class MAVLink_waypoint_clear_all_message(MAVLink_message): + ''' + Delete all waypoints at once. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL + name = 'WAYPOINT_CLEAR_ALL' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 229 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_clear_all_message.id, MAVLink_waypoint_clear_all_message.name) + self._fieldnames = MAVLink_waypoint_clear_all_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_reached_message(MAVLink_message): + ''' + A certain waypoint has been reached. The system will either + hold this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REACHED + name = 'WAYPOINT_REACHED' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 21 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_reached_message.id, MAVLink_waypoint_reached_message.name) + self._fieldnames = MAVLink_waypoint_reached_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_ack_message(MAVLink_message): + ''' + Ack message during waypoint handling. The type field states if + this message is a positive ack (type=0) or if an error + happened (type=non-zero). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_ACK + name = 'WAYPOINT_ACK' + fieldnames = ['target_system', 'target_component', 'type'] + ordered_fieldnames = [ 'target_system', 'target_component', 'type' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 214 + + def __init__(self, target_system, target_component, type): + MAVLink_message.__init__(self, MAVLink_waypoint_ack_message.id, MAVLink_waypoint_ack_message.name) + self._fieldnames = MAVLink_waypoint_ack_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.type = type + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type)) + +class MAVLink_gps_set_global_origin_message(MAVLink_message): + ''' + As local waypoints exist, the global waypoint reference allows + to transform between the local coordinate frame and the global + (GPS) coordinate frame. This can be necessary when e.g. in- + and outdoor settings are connected and the MAV should move + from in- to outdoor. + ''' + id = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN + name = 'GPS_SET_GLOBAL_ORIGIN' + fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'target_system', 'target_component', 'latitude', 'longitude', 'altitude' ] + format = '>BBiii' + native_format = bytearray('>BBiii', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, target_system, target_component, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_set_global_origin_message.id, MAVLink_gps_set_global_origin_message.name) + self._fieldnames = MAVLink_gps_set_global_origin_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude)) + +class MAVLink_gps_local_origin_set_message(MAVLink_message): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + ''' + id = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET + name = 'GPS_LOCAL_ORIGIN_SET' + fieldnames = ['latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'latitude', 'longitude', 'altitude' ] + format = '>iii' + native_format = bytearray('>iii', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 14 + + def __init__(self, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_local_origin_set_message.id, MAVLink_gps_local_origin_set_message.name) + self._fieldnames = MAVLink_gps_local_origin_set_message.fieldnames + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude)) + +class MAVLink_local_position_setpoint_set_message(MAVLink_message): + ''' + Set the setpoint for a local position controller. This is the + position in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the onboard + position controller. As some MAVs have a degree of freedom in + yaw (e.g. all helicopters/quadrotors), the desired yaw angle + is part of the message. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET + name = 'LOCAL_POSITION_SETPOINT_SET' + fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'x', 'y', 'z', 'yaw' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 206 + + def __init__(self, target_system, target_component, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_set_message.id, MAVLink_local_position_setpoint_set_message.name) + self._fieldnames = MAVLink_local_position_setpoint_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw)) + +class MAVLink_local_position_setpoint_message(MAVLink_message): + ''' + Transmit the current local setpoint of the controller to other + MAVs (collision avoidance) and to the GCS. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT + name = 'LOCAL_POSITION_SETPOINT' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 50 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_message.id, MAVLink_local_position_setpoint_message.name) + self._fieldnames = MAVLink_local_position_setpoint_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_control_status_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_CONTROL_STATUS + name = 'CONTROL_STATUS' + fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw'] + ordered_fieldnames = [ 'position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw' ] + format = '>BBBBBBBB' + native_format = bytearray('>BBBBBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 157 + + def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + MAVLink_message.__init__(self, MAVLink_control_status_message.id, MAVLink_control_status_message.name) + self._fieldnames = MAVLink_control_status_message.fieldnames + self.position_fix = position_fix + self.vision_fix = vision_fix + self.gps_fix = gps_fix + self.ahrs_health = ahrs_health + self.control_att = control_att + self.control_pos_xy = control_pos_xy + self.control_pos_z = control_pos_z + self.control_pos_yaw = control_pos_yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw)) + +class MAVLink_safety_set_allowed_area_message(MAVLink_message): + ''' + Set a safety zone (volume), which is defined by two corners of + a cube. This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. Safety + areas are often enforced by national or competition + regulations. + ''' + id = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA + name = 'SAFETY_SET_ALLOWED_AREA' + fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>BBBffffff' + native_format = bytearray('>BBBffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_set_allowed_area_message.id, MAVLink_safety_set_allowed_area_message.name) + self._fieldnames = MAVLink_safety_set_allowed_area_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_safety_allowed_area_message(MAVLink_message): + ''' + Read out the safety zone the MAV currently assumes. + ''' + id = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA + name = 'SAFETY_ALLOWED_AREA' + fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>Bffffff' + native_format = bytearray('>Bffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 108 + + def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_allowed_area_message.id, MAVLink_safety_allowed_area_message.name) + self._fieldnames = MAVLink_safety_allowed_area_message.fieldnames + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST + name = 'SET_ROLL_PITCH_YAW_THRUST' + fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_thrust_message.id, MAVLink_set_roll_pitch_yaw_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST + name = 'SET_ROLL_PITCH_YAW_SPEED_THRUST' + fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 95 + + def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_speed_thrust_message.id, MAVLink_set_roll_pitch_yaw_speed_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_speed_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 5 + + def __init__(self, time_us, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active + on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 127 + + def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_nav_controller_output_message(MAVLink_message): + ''' + Outputs of the APM navigation controller. The primary use of + this message is to check the response and signs of the + controller before actual flight and to assist with tuning + controller parameters + ''' + id = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT + name = 'NAV_CONTROLLER_OUTPUT' + fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error'] + ordered_fieldnames = [ 'nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error' ] + format = '>ffhhHfff' + native_format = bytearray('>ffhhHfff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 57 + + def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + MAVLink_message.__init__(self, MAVLink_nav_controller_output_message.id, MAVLink_nav_controller_output_message.name) + self._fieldnames = MAVLink_nav_controller_output_message.fieldnames + self.nav_roll = nav_roll + self.nav_pitch = nav_pitch + self.nav_bearing = nav_bearing + self.target_bearing = target_bearing + self.wp_dist = wp_dist + self.alt_error = alt_error + self.aspd_error = aspd_error + self.xtrack_error = xtrack_error + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error)) + +class MAVLink_position_target_message(MAVLink_message): + ''' + The goal position of the system. This position is the input to + any navigation or path planning algorithm and does NOT + represent the current controller setpoint. + ''' + id = MAVLINK_MSG_ID_POSITION_TARGET + name = 'POSITION_TARGET' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_position_target_message.id, MAVLink_position_target_message.name) + self._fieldnames = MAVLink_position_target_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_state_correction_message(MAVLink_message): + ''' + Corrects the systems state by adding an error correction term + to the position and velocity, and by rotating the attitude by + a correction angle. + ''' + id = MAVLINK_MSG_ID_STATE_CORRECTION + name = 'STATE_CORRECTION' + fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr'] + ordered_fieldnames = [ 'xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr' ] + format = '>fffffffff' + native_format = bytearray('>fffffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 130 + + def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + MAVLink_message.__init__(self, MAVLink_state_correction_message.id, MAVLink_state_correction_message.name) + self._fieldnames = MAVLink_state_correction_message.fieldnames + self.xErr = xErr + self.yErr = yErr + self.zErr = zErr + self.rollErr = rollErr + self.pitchErr = pitchErr + self.yawErr = yawErr + self.vxErr = vxErr + self.vyErr = vyErr + self.vzErr = vzErr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr)) + +class MAVLink_set_altitude_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_SET_ALTITUDE + name = 'SET_ALTITUDE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BI' + native_format = bytearray('>BI', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 119 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_altitude_message.id, MAVLink_set_altitude_message.name) + self._fieldnames = MAVLink_set_altitude_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode)) + +class MAVLink_request_data_stream_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_REQUEST_DATA_STREAM + name = 'REQUEST_DATA_STREAM' + fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop'] + ordered_fieldnames = [ 'target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop' ] + format = '>BBBHB' + native_format = bytearray('>BBBHB', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 193 + + def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + MAVLink_message.__init__(self, MAVLink_request_data_stream_message.id, MAVLink_request_data_stream_message.name) + self._fieldnames = MAVLink_request_data_stream_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.req_stream_id = req_stream_id + self.req_message_rate = req_message_rate + self.start_stop = start_stop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop)) + +class MAVLink_hil_state_message(MAVLink_message): + ''' + This packet is useful for high throughput + applications such as hardware in the loop simulations. + ''' + id = MAVLINK_MSG_ID_HIL_STATE + name = 'HIL_STATE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc' ] + format = '>Qffffffiiihhhhhh' + native_format = bytearray('>Qffffffiiihhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 191 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + MAVLink_message.__init__(self, MAVLink_hil_state_message.id, MAVLink_hil_state_message.name) + self._fieldnames = MAVLink_hil_state_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc)) + +class MAVLink_hil_controls_message(MAVLink_message): + ''' + Hardware in the loop control outputs + ''' + id = MAVLINK_MSG_ID_HIL_CONTROLS + name = 'HIL_CONTROLS' + fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode'] + ordered_fieldnames = [ 'time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode' ] + format = '>QffffBB' + native_format = bytearray('>QffffBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 236 + + def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + MAVLink_message.__init__(self, MAVLink_hil_controls_message.id, MAVLink_hil_controls_message.name) + self._fieldnames = MAVLink_hil_controls_message.fieldnames + self.time_us = time_us + self.roll_ailerons = roll_ailerons + self.pitch_elevator = pitch_elevator + self.yaw_rudder = yaw_rudder + self.throttle = throttle + self.mode = mode + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode)) + +class MAVLink_manual_control_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_MANUAL_CONTROL + name = 'MANUAL_CONTROL' + fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual'] + ordered_fieldnames = [ 'target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual' ] + format = '>BffffBBBB' + native_format = bytearray('>BffffBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 158 + + def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + MAVLink_message.__init__(self, MAVLink_manual_control_message.id, MAVLink_manual_control_message.name) + self._fieldnames = MAVLink_manual_control_message.fieldnames + self.target = target + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + self.roll_manual = roll_manual + self.pitch_manual = pitch_manual + self.yaw_manual = yaw_manual + self.thrust_manual = thrust_manual + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual)) + +class MAVLink_rc_channels_override_message(MAVLink_message): + ''' + The RAW values of the RC channels sent to the MAV to override + info received from the RC radio. A value of -1 means no change + to that channel. A value of 0 means control of that channel + should be released back to the RC radio. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE + name = 'RC_CHANNELS_OVERRIDE' + fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw' ] + format = '>BBHHHHHHHH' + native_format = bytearray('>BBHHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 143 + + def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + MAVLink_message.__init__(self, MAVLink_rc_channels_override_message.id, MAVLink_rc_channels_override_message.name) + self._fieldnames = MAVLink_rc_channels_override_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw)) + +class MAVLink_global_position_int_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). The position is in GPS-frame (right-handed, + Z-up) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION_INT + name = 'GLOBAL_POSITION_INT' + fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>iiihhh' + native_format = bytearray('>iiihhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 104 + + def __init__(self, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_int_message.id, MAVLink_global_position_int_message.name) + self._fieldnames = MAVLink_global_position_int_message.fieldnames + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_vfr_hud_message(MAVLink_message): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + ''' + id = MAVLINK_MSG_ID_VFR_HUD + name = 'VFR_HUD' + fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb'] + ordered_fieldnames = [ 'airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb' ] + format = '>ffhHff' + native_format = bytearray('>ffhHff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 123 + + def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb): + MAVLink_message.__init__(self, MAVLink_vfr_hud_message.id, MAVLink_vfr_hud_message.name) + self._fieldnames = MAVLink_vfr_hud_message.fieldnames + self.airspeed = airspeed + self.groundspeed = groundspeed + self.heading = heading + self.throttle = throttle + self.alt = alt + self.climb = climb + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb)) + +class MAVLink_command_message(MAVLink_message): + ''' + Send a command with up to four parameters to the MAV + ''' + id = MAVLINK_MSG_ID_COMMAND + name = 'COMMAND' + fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4'] + ordered_fieldnames = [ 'target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4' ] + format = '>BBBBffff' + native_format = bytearray('>BBBBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 131 + + def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + MAVLink_message.__init__(self, MAVLink_command_message.id, MAVLink_command_message.name) + self._fieldnames = MAVLink_command_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.command = command + self.confirmation = confirmation + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4)) + +class MAVLink_command_ack_message(MAVLink_message): + ''' + Report status of a command. Includes feedback wether the + command was executed + ''' + id = MAVLINK_MSG_ID_COMMAND_ACK + name = 'COMMAND_ACK' + fieldnames = ['command', 'result'] + ordered_fieldnames = [ 'command', 'result' ] + format = '>ff' + native_format = bytearray('>ff', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 8 + + def __init__(self, command, result): + MAVLink_message.__init__(self, MAVLink_command_ack_message.id, MAVLink_command_ack_message.name) + self._fieldnames = MAVLink_command_ack_message.fieldnames + self.command = command + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result)) + +class MAVLink_optical_flow_message(MAVLink_message): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + ''' + id = MAVLINK_MSG_ID_OPTICAL_FLOW + name = 'OPTICAL_FLOW' + fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance'] + ordered_fieldnames = [ 'time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance' ] + format = '>QBhhBf' + native_format = bytearray('>QBhhBf', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 174 + + def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + MAVLink_message.__init__(self, MAVLink_optical_flow_message.id, MAVLink_optical_flow_message.name) + self._fieldnames = MAVLink_optical_flow_message.fieldnames + self.time = time + self.sensor_id = sensor_id + self.flow_x = flow_x + self.flow_y = flow_y + self.quality = quality + self.ground_distance = ground_distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance)) + +class MAVLink_object_detection_event_message(MAVLink_message): + ''' + Object has been detected + ''' + id = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT + name = 'OBJECT_DETECTION_EVENT' + fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance'] + ordered_fieldnames = [ 'time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance' ] + format = '>IHB20sBff' + native_format = bytearray('>IHBcBff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 20, 0, 0, 0] + crc_extra = 155 + + def __init__(self, time, object_id, type, name, quality, bearing, distance): + MAVLink_message.__init__(self, MAVLink_object_detection_event_message.id, MAVLink_object_detection_event_message.name) + self._fieldnames = MAVLink_object_detection_event_message.fieldnames + self.time = time + self.object_id = object_id + self.type = type + self.name = name + self.quality = quality + self.bearing = bearing + self.distance = distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance)) + +class MAVLink_debug_vect_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_DEBUG_VECT + name = 'DEBUG_VECT' + fieldnames = ['name', 'usec', 'x', 'y', 'z'] + ordered_fieldnames = [ 'name', 'usec', 'x', 'y', 'z' ] + format = '>10sQfff' + native_format = bytearray('>cQfff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [10, 0, 0, 0, 0] + crc_extra = 178 + + def __init__(self, name, usec, x, y, z): + MAVLink_message.__init__(self, MAVLink_debug_vect_message.id, MAVLink_debug_vect_message.name) + self._fieldnames = MAVLink_debug_vect_message.fieldnames + self.name = name + self.usec = usec + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z)) + +class MAVLink_named_value_float_message(MAVLink_message): + ''' + Send a key-value pair as float. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT + name = 'NAMED_VALUE_FLOAT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10sf' + native_format = bytearray('>cf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 224 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_float_message.id, MAVLink_named_value_float_message.name) + self._fieldnames = MAVLink_named_value_float_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value)) + +class MAVLink_named_value_int_message(MAVLink_message): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_INT + name = 'NAMED_VALUE_INT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10si' + native_format = bytearray('>ci', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 60 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_int_message.id, MAVLink_named_value_int_message.name) + self._fieldnames = MAVLink_named_value_int_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value)) + +class MAVLink_statustext_message(MAVLink_message): + ''' + Status text message. These messages are printed in yellow in + the COMM console of QGroundControl. WARNING: They consume + quite some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages are + buffered on the MCU and sent only at a limited rate (e.g. 10 + Hz). + ''' + id = MAVLINK_MSG_ID_STATUSTEXT + name = 'STATUSTEXT' + fieldnames = ['severity', 'text'] + ordered_fieldnames = [ 'severity', 'text' ] + format = '>B50b' + native_format = bytearray('>Bb', 'ascii') + orders = [0, 1] + lengths = [1, 50] + array_lengths = [0, 50] + crc_extra = 106 + + def __init__(self, severity, text): + MAVLink_message.__init__(self, MAVLink_statustext_message.id, MAVLink_statustext_message.name) + self._fieldnames = MAVLink_statustext_message.fieldnames + self.severity = severity + self.text = text + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>B50b', self.severity, self.text[0], self.text[1], self.text[2], self.text[3], self.text[4], self.text[5], self.text[6], self.text[7], self.text[8], self.text[9], self.text[10], self.text[11], self.text[12], self.text[13], self.text[14], self.text[15], self.text[16], self.text[17], self.text[18], self.text[19], self.text[20], self.text[21], self.text[22], self.text[23], self.text[24], self.text[25], self.text[26], self.text[27], self.text[28], self.text[29], self.text[30], self.text[31], self.text[32], self.text[33], self.text[34], self.text[35], self.text[36], self.text[37], self.text[38], self.text[39], self.text[40], self.text[41], self.text[42], self.text[43], self.text[44], self.text[45], self.text[46], self.text[47], self.text[48], self.text[49])) + +class MAVLink_debug_message(MAVLink_message): + ''' + Send a debug value. The index is used to discriminate between + values. These values show up in the plot of QGroundControl as + DEBUG N. + ''' + id = MAVLINK_MSG_ID_DEBUG + name = 'DEBUG' + fieldnames = ['ind', 'value'] + ordered_fieldnames = [ 'ind', 'value' ] + format = '>Bf' + native_format = bytearray('>Bf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 7 + + def __init__(self, ind, value): + MAVLink_message.__init__(self, MAVLink_debug_message.id, MAVLink_debug_message.name) + self._fieldnames = MAVLink_debug_message.fieldnames + self.ind = ind + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value)) + + +mavlink_map = { + MAVLINK_MSG_ID_SENSOR_OFFSETS : MAVLink_sensor_offsets_message, + MAVLINK_MSG_ID_SET_MAG_OFFSETS : MAVLink_set_mag_offsets_message, + MAVLINK_MSG_ID_MEMINFO : MAVLink_meminfo_message, + MAVLINK_MSG_ID_AP_ADC : MAVLink_ap_adc_message, + MAVLINK_MSG_ID_DIGICAM_CONFIGURE : MAVLink_digicam_configure_message, + MAVLINK_MSG_ID_DIGICAM_CONTROL : MAVLink_digicam_control_message, + MAVLINK_MSG_ID_MOUNT_CONFIGURE : MAVLink_mount_configure_message, + MAVLINK_MSG_ID_MOUNT_CONTROL : MAVLink_mount_control_message, + MAVLINK_MSG_ID_MOUNT_STATUS : MAVLink_mount_status_message, + MAVLINK_MSG_ID_FENCE_POINT : MAVLink_fence_point_message, + MAVLINK_MSG_ID_FENCE_FETCH_POINT : MAVLink_fence_fetch_point_message, + MAVLINK_MSG_ID_FENCE_STATUS : MAVLink_fence_status_message, + MAVLINK_MSG_ID_AHRS : MAVLink_ahrs_message, + MAVLINK_MSG_ID_SIMSTATE : MAVLink_simstate_message, + MAVLINK_MSG_ID_HWSTATUS : MAVLink_hwstatus_message, + MAVLINK_MSG_ID_RADIO : MAVLink_radio_message, + MAVLINK_MSG_ID_HEARTBEAT : MAVLink_heartbeat_message, + MAVLINK_MSG_ID_BOOT : MAVLink_boot_message, + MAVLINK_MSG_ID_SYSTEM_TIME : MAVLink_system_time_message, + MAVLINK_MSG_ID_PING : MAVLink_ping_message, + MAVLINK_MSG_ID_SYSTEM_TIME_UTC : MAVLink_system_time_utc_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : MAVLink_change_operator_control_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : MAVLink_change_operator_control_ack_message, + MAVLINK_MSG_ID_AUTH_KEY : MAVLink_auth_key_message, + MAVLINK_MSG_ID_ACTION_ACK : MAVLink_action_ack_message, + MAVLINK_MSG_ID_ACTION : MAVLink_action_message, + MAVLINK_MSG_ID_SET_MODE : MAVLink_set_mode_message, + MAVLINK_MSG_ID_SET_NAV_MODE : MAVLink_set_nav_mode_message, + MAVLINK_MSG_ID_PARAM_REQUEST_READ : MAVLink_param_request_read_message, + MAVLINK_MSG_ID_PARAM_REQUEST_LIST : MAVLink_param_request_list_message, + MAVLINK_MSG_ID_PARAM_VALUE : MAVLink_param_value_message, + MAVLINK_MSG_ID_PARAM_SET : MAVLink_param_set_message, + MAVLINK_MSG_ID_GPS_RAW_INT : MAVLink_gps_raw_int_message, + MAVLINK_MSG_ID_SCALED_IMU : MAVLink_scaled_imu_message, + MAVLINK_MSG_ID_GPS_STATUS : MAVLink_gps_status_message, + MAVLINK_MSG_ID_RAW_IMU : MAVLink_raw_imu_message, + MAVLINK_MSG_ID_RAW_PRESSURE : MAVLink_raw_pressure_message, + MAVLINK_MSG_ID_SCALED_PRESSURE : MAVLink_scaled_pressure_message, + MAVLINK_MSG_ID_ATTITUDE : MAVLink_attitude_message, + MAVLINK_MSG_ID_LOCAL_POSITION : MAVLink_local_position_message, + MAVLINK_MSG_ID_GLOBAL_POSITION : MAVLink_global_position_message, + MAVLINK_MSG_ID_GPS_RAW : MAVLink_gps_raw_message, + MAVLINK_MSG_ID_SYS_STATUS : MAVLink_sys_status_message, + MAVLINK_MSG_ID_RC_CHANNELS_RAW : MAVLink_rc_channels_raw_message, + MAVLINK_MSG_ID_RC_CHANNELS_SCALED : MAVLink_rc_channels_scaled_message, + MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : MAVLink_servo_output_raw_message, + MAVLINK_MSG_ID_WAYPOINT : MAVLink_waypoint_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST : MAVLink_waypoint_request_message, + MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : MAVLink_waypoint_set_current_message, + MAVLINK_MSG_ID_WAYPOINT_CURRENT : MAVLink_waypoint_current_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : MAVLink_waypoint_request_list_message, + MAVLINK_MSG_ID_WAYPOINT_COUNT : MAVLink_waypoint_count_message, + MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : MAVLink_waypoint_clear_all_message, + MAVLINK_MSG_ID_WAYPOINT_REACHED : MAVLink_waypoint_reached_message, + MAVLINK_MSG_ID_WAYPOINT_ACK : MAVLink_waypoint_ack_message, + MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : MAVLink_gps_set_global_origin_message, + MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : MAVLink_gps_local_origin_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : MAVLink_local_position_setpoint_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : MAVLink_local_position_setpoint_message, + MAVLINK_MSG_ID_CONTROL_STATUS : MAVLink_control_status_message, + MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : MAVLink_safety_set_allowed_area_message, + MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : MAVLink_safety_allowed_area_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : MAVLink_set_roll_pitch_yaw_thrust_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : MAVLink_set_roll_pitch_yaw_speed_thrust_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_thrust_setpoint_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, + MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : MAVLink_nav_controller_output_message, + MAVLINK_MSG_ID_POSITION_TARGET : MAVLink_position_target_message, + MAVLINK_MSG_ID_STATE_CORRECTION : MAVLink_state_correction_message, + MAVLINK_MSG_ID_SET_ALTITUDE : MAVLink_set_altitude_message, + MAVLINK_MSG_ID_REQUEST_DATA_STREAM : MAVLink_request_data_stream_message, + MAVLINK_MSG_ID_HIL_STATE : MAVLink_hil_state_message, + MAVLINK_MSG_ID_HIL_CONTROLS : MAVLink_hil_controls_message, + MAVLINK_MSG_ID_MANUAL_CONTROL : MAVLink_manual_control_message, + MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : MAVLink_rc_channels_override_message, + MAVLINK_MSG_ID_GLOBAL_POSITION_INT : MAVLink_global_position_int_message, + MAVLINK_MSG_ID_VFR_HUD : MAVLink_vfr_hud_message, + MAVLINK_MSG_ID_COMMAND : MAVLink_command_message, + MAVLINK_MSG_ID_COMMAND_ACK : MAVLink_command_ack_message, + MAVLINK_MSG_ID_OPTICAL_FLOW : MAVLink_optical_flow_message, + MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : MAVLink_object_detection_event_message, + MAVLINK_MSG_ID_DEBUG_VECT : MAVLink_debug_vect_message, + MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : MAVLink_named_value_float_message, + MAVLINK_MSG_ID_NAMED_VALUE_INT : MAVLink_named_value_int_message, + MAVLINK_MSG_ID_STATUSTEXT : MAVLink_statustext_message, + MAVLINK_MSG_ID_DEBUG : MAVLink_debug_message, +} + +class MAVError(Exception): + '''MAVLink error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + +class MAVString(str): + '''NUL terminated string''' + def __init__(self, s): + str.__init__(self) + def __str__(self): + i = self.find(chr(0)) + if i == -1: + return self[:] + return self[0:i] + +class MAVLink_bad_data(MAVLink_message): + ''' + a piece of bad data in a mavlink stream + ''' + def __init__(self, data, reason): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') + self._fieldnames = ['data', 'reason'] + self.data = data + self.reason = reason + self._msgbuf = data + + def __str__(self): + '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' + return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) + +class MAVLink(object): + '''MAVLink protocol handling class''' + def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): + self.seq = 0 + self.file = file + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.callback = None + self.callback_args = None + self.callback_kwargs = None + self.send_callback = None + self.send_callback_args = None + self.send_callback_kwargs = None + self.buf = bytearray() + self.expected_length = 8 + self.have_prefix_error = False + self.robust_parsing = False + self.protocol_marker = 85 + self.little_endian = False + self.crc_extra = False + self.sort_fields = False + self.total_packets_sent = 0 + self.total_bytes_sent = 0 + self.total_packets_received = 0 + self.total_bytes_received = 0 + self.total_receive_errors = 0 + self.startup_time = time.time() + if native_supported and (use_native or native_testing or native_force): + print("NOTE: mavnative is currently beta-test code") + self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) + else: + self.native = None + if native_testing: + self.test_buf = bytearray() + + def set_callback(self, callback, *args, **kwargs): + self.callback = callback + self.callback_args = args + self.callback_kwargs = kwargs + + def set_send_callback(self, callback, *args, **kwargs): + self.send_callback = callback + self.send_callback_args = args + self.send_callback_kwargs = kwargs + + def send(self, mavmsg): + '''send a MAVLink message''' + buf = mavmsg.pack(self) + self.file.write(buf) + self.seq = (self.seq + 1) % 256 + self.total_packets_sent += 1 + self.total_bytes_sent += len(buf) + if self.send_callback: + self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) + + def bytes_needed(self): + '''return number of bytes needed for next parsing stage''' + if self.native: + ret = self.native.expected_length - len(self.buf) + else: + ret = self.expected_length - len(self.buf) + + if ret <= 0: + return 1 + return ret + + def __parse_char_native(self, c): + '''this method exists only to see in profiling results''' + m = self.native.parse_chars(c) + return m + + def __callbacks(self, msg): + '''this method exists only to make profiling results easier to read''' + if self.callback: + self.callback(msg, *self.callback_args, **self.callback_kwargs) + + def parse_char(self, c): + '''input some data bytes, possibly returning a new message''' + self.buf.extend(c) + + self.total_bytes_received += len(c) + + if self.native: + if native_testing: + self.test_buf.extend(c) + m = self.__parse_char_native(self.test_buf) + m2 = self.__parse_char_legacy() + if m2 != m: + print("Native: %s\nLegacy: %s\n" % (m, m2)) + raise Exception('Native vs. Legacy mismatch') + else: + m = self.__parse_char_native(self.buf) + else: + m = self.__parse_char_legacy() + + if m != None: + self.total_packets_received += 1 + self.__callbacks(m) + + return m + + def __parse_char_legacy(self): + '''input some data bytes, possibly returning a new message (uses no native code)''' + if len(self.buf) >= 1 and self.buf[0] != 85: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 85: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' MAV. + Also used to return a point from MAV -> GCS + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + count : total number of points (for sanity checking) (uint8_t) + lat : Latitude of point (float) + lng : Longitude of point (float) + + ''' + return MAVLink_fence_point_message(target_system, target_component, idx, count, lat, lng) + + def fence_point_send(self, target_system, target_component, idx, count, lat, lng): + ''' + A fence point. Used to set a point when from GCS -> MAV. + Also used to return a point from MAV -> GCS + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + count : total number of points (for sanity checking) (uint8_t) + lat : Latitude of point (float) + lng : Longitude of point (float) + + ''' + return self.send(self.fence_point_encode(target_system, target_component, idx, count, lat, lng)) + + def fence_fetch_point_encode(self, target_system, target_component, idx): + ''' + Request a current fence point from MAV + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + + ''' + return MAVLink_fence_fetch_point_message(target_system, target_component, idx) + + def fence_fetch_point_send(self, target_system, target_component, idx): + ''' + Request a current fence point from MAV + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + + ''' + return self.send(self.fence_fetch_point_encode(target_system, target_component, idx)) + + def fence_status_encode(self, breach_status, breach_count, breach_type, breach_time): + ''' + Status of geo-fencing. Sent in extended status stream when + fencing enabled + + breach_status : 0 if currently inside fence, 1 if outside (uint8_t) + breach_count : number of fence breaches (uint16_t) + breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) + breach_time : time of last breach in milliseconds since boot (uint32_t) + + ''' + return MAVLink_fence_status_message(breach_status, breach_count, breach_type, breach_time) + + def fence_status_send(self, breach_status, breach_count, breach_type, breach_time): + ''' + Status of geo-fencing. Sent in extended status stream when + fencing enabled + + breach_status : 0 if currently inside fence, 1 if outside (uint8_t) + breach_count : number of fence breaches (uint16_t) + breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) + breach_time : time of last breach in milliseconds since boot (uint32_t) + + ''' + return self.send(self.fence_status_encode(breach_status, breach_count, breach_type, breach_time)) + + def ahrs_encode(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): + ''' + Status of DCM attitude estimator + + omegaIx : X gyro drift estimate rad/s (float) + omegaIy : Y gyro drift estimate rad/s (float) + omegaIz : Z gyro drift estimate rad/s (float) + accel_weight : average accel_weight (float) + renorm_val : average renormalisation value (float) + error_rp : average error_roll_pitch value (float) + error_yaw : average error_yaw value (float) + + ''' + return MAVLink_ahrs_message(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw) + + def ahrs_send(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): + ''' + Status of DCM attitude estimator + + omegaIx : X gyro drift estimate rad/s (float) + omegaIy : Y gyro drift estimate rad/s (float) + omegaIz : Z gyro drift estimate rad/s (float) + accel_weight : average accel_weight (float) + renorm_val : average renormalisation value (float) + error_rp : average error_roll_pitch value (float) + error_yaw : average error_yaw value (float) + + ''' + return self.send(self.ahrs_encode(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw)) + + def simstate_encode(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): + ''' + Status of simulation environment, if used + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + + ''' + return MAVLink_simstate_message(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro) + + def simstate_send(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): + ''' + Status of simulation environment, if used + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + + ''' + return self.send(self.simstate_encode(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro)) + + def hwstatus_encode(self, Vcc, I2Cerr): + ''' + Status of key hardware + + Vcc : board voltage (mV) (uint16_t) + I2Cerr : I2C error count (uint8_t) + + ''' + return MAVLink_hwstatus_message(Vcc, I2Cerr) + + def hwstatus_send(self, Vcc, I2Cerr): + ''' + Status of key hardware + + Vcc : board voltage (mV) (uint16_t) + I2Cerr : I2C error count (uint8_t) + + ''' + return self.send(self.hwstatus_encode(Vcc, I2Cerr)) + + def radio_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio + + rssi : local signal strength (uint8_t) + remrssi : remote signal strength (uint8_t) + txbuf : how full the tx buffer is as a percentage (uint8_t) + noise : background noise level (uint8_t) + remnoise : remote background noise level (uint8_t) + rxerrors : receive errors (uint16_t) + fixed : count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio + + rssi : local signal strength (uint8_t) + remrssi : remote signal strength (uint8_t) + txbuf : how full the tx buffer is as a percentage (uint8_t) + noise : background noise level (uint8_t) + remnoise : remote background noise level (uint8_t) + rxerrors : receive errors (uint16_t) + fixed : count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def heartbeat_encode(self, type, autopilot, mavlink_version=2): + ''' + The heartbeat message shows that a system is present and responding. + The type of the MAV and Autopilot hardware allow the + receiving system to treat further messages from this + system appropriate (e.g. by laying out the user + interface based on the autopilot). + + type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) + autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t) + mavlink_version : MAVLink version (uint8_t) + + ''' + return MAVLink_heartbeat_message(type, autopilot, mavlink_version) + + def heartbeat_send(self, type, autopilot, mavlink_version=2): + ''' + The heartbeat message shows that a system is present and responding. + The type of the MAV and Autopilot hardware allow the + receiving system to treat further messages from this + system appropriate (e.g. by laying out the user + interface based on the autopilot). + + type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) + autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t) + mavlink_version : MAVLink version (uint8_t) + + ''' + return self.send(self.heartbeat_encode(type, autopilot, mavlink_version)) + + def boot_encode(self, version): + ''' + The boot message indicates that a system is starting. The onboard + software version allows to keep track of onboard + soft/firmware revisions. + + version : The onboard software version (uint32_t) + + ''' + return MAVLink_boot_message(version) + + def boot_send(self, version): + ''' + The boot message indicates that a system is starting. The onboard + software version allows to keep track of onboard + soft/firmware revisions. + + version : The onboard software version (uint32_t) + + ''' + return self.send(self.boot_encode(version)) + + def system_time_encode(self, time_usec): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + + time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) + + ''' + return MAVLink_system_time_message(time_usec) + + def system_time_send(self, time_usec): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + + time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) + + ''' + return self.send(self.system_time_encode(time_usec)) + + def ping_encode(self, seq, target_system, target_component, time): + ''' + A ping message either requesting or responding to a ping. This allows + to measure the system latencies, including serial + port, radio modem and UDP connections. + + seq : PING sequence (uint32_t) + target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + time : Unix timestamp in microseconds (uint64_t) + + ''' + return MAVLink_ping_message(seq, target_system, target_component, time) + + def ping_send(self, seq, target_system, target_component, time): + ''' + A ping message either requesting or responding to a ping. This allows + to measure the system latencies, including serial + port, radio modem and UDP connections. + + seq : PING sequence (uint32_t) + target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + time : Unix timestamp in microseconds (uint64_t) + + ''' + return self.send(self.ping_encode(seq, target_system, target_component, time)) + + def system_time_utc_encode(self, utc_date, utc_time): + ''' + UTC date and time from GPS module + + utc_date : GPS UTC date ddmmyy (uint32_t) + utc_time : GPS UTC time hhmmss (uint32_t) + + ''' + return MAVLink_system_time_utc_message(utc_date, utc_time) + + def system_time_utc_send(self, utc_date, utc_time): + ''' + UTC date and time from GPS module + + utc_date : GPS UTC date ddmmyy (uint32_t) + utc_time : GPS UTC time hhmmss (uint32_t) + + ''' + return self.send(self.system_time_utc_encode(utc_date, utc_time)) + + def change_operator_control_encode(self, target_system, control_request, version, passkey): + ''' + Request to control this MAV + + target_system : System the GCS requests control for (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) + passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) + + ''' + return MAVLink_change_operator_control_message(target_system, control_request, version, passkey) + + def change_operator_control_send(self, target_system, control_request, version, passkey): + ''' + Request to control this MAV + + target_system : System the GCS requests control for (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) + passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) + + ''' + return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) + + def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): + ''' + Accept / deny control of this MAV + + gcs_system_id : ID of the GCS this message (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) + + ''' + return MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) + + def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): + ''' + Accept / deny control of this MAV + + gcs_system_id : ID of the GCS this message (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) + + ''' + return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) + + def auth_key_encode(self, key): + ''' + Emit an encrypted signature / key identifying this system. PLEASE + NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for + true safety. + + key : key (char) + + ''' + return MAVLink_auth_key_message(key) + + def auth_key_send(self, key): + ''' + Emit an encrypted signature / key identifying this system. PLEASE + NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for + true safety. + + key : key (char) + + ''' + return self.send(self.auth_key_encode(key)) + + def action_ack_encode(self, action, result): + ''' + This message acknowledges an action. IMPORTANT: The acknowledgement + can be also negative, e.g. the MAV rejects a reset + message because it is in-flight. The action ids are + defined in ENUM MAV_ACTION in + mavlink/include/mavlink_types.h + + action : The action id (uint8_t) + result : 0: Action DENIED, 1: Action executed (uint8_t) + + ''' + return MAVLink_action_ack_message(action, result) + + def action_ack_send(self, action, result): + ''' + This message acknowledges an action. IMPORTANT: The acknowledgement + can be also negative, e.g. the MAV rejects a reset + message because it is in-flight. The action ids are + defined in ENUM MAV_ACTION in + mavlink/include/mavlink_types.h + + action : The action id (uint8_t) + result : 0: Action DENIED, 1: Action executed (uint8_t) + + ''' + return self.send(self.action_ack_encode(action, result)) + + def action_encode(self, target, target_component, action): + ''' + An action message allows to execute a certain onboard action. These + include liftoff, land, storing parameters too EEPROM, + shutddown, etc. The action ids are defined in ENUM + MAV_ACTION in mavlink/include/mavlink_types.h + + target : The system executing the action (uint8_t) + target_component : The component executing the action (uint8_t) + action : The action id (uint8_t) + + ''' + return MAVLink_action_message(target, target_component, action) + + def action_send(self, target, target_component, action): + ''' + An action message allows to execute a certain onboard action. These + include liftoff, land, storing parameters too EEPROM, + shutddown, etc. The action ids are defined in ENUM + MAV_ACTION in mavlink/include/mavlink_types.h + + target : The system executing the action (uint8_t) + target_component : The component executing the action (uint8_t) + action : The action id (uint8_t) + + ''' + return self.send(self.action_encode(target, target_component, action)) + + def set_mode_encode(self, target, mode): + ''' + Set the system mode, as defined by enum MAV_MODE in + mavlink/include/mavlink_types.h. There is no target + component id as the mode is by definition for the + overall aircraft, not only for one component. + + target : The system setting the mode (uint8_t) + mode : The new mode (uint8_t) + + ''' + return MAVLink_set_mode_message(target, mode) + + def set_mode_send(self, target, mode): + ''' + Set the system mode, as defined by enum MAV_MODE in + mavlink/include/mavlink_types.h. There is no target + component id as the mode is by definition for the + overall aircraft, not only for one component. + + target : The system setting the mode (uint8_t) + mode : The new mode (uint8_t) + + ''' + return self.send(self.set_mode_encode(target, mode)) + + def set_nav_mode_encode(self, target, nav_mode): + ''' + Set the system navigation mode, as defined by enum MAV_NAV_MODE in + mavlink/include/mavlink_types.h. The navigation mode + applies to the whole aircraft and thus all components. + + target : The system setting the mode (uint8_t) + nav_mode : The new navigation mode (uint8_t) + + ''' + return MAVLink_set_nav_mode_message(target, nav_mode) + + def set_nav_mode_send(self, target, nav_mode): + ''' + Set the system navigation mode, as defined by enum MAV_NAV_MODE in + mavlink/include/mavlink_types.h. The navigation mode + applies to the whole aircraft and thus all components. + + target : The system setting the mode (uint8_t) + nav_mode : The new navigation mode (uint8_t) + + ''' + return self.send(self.set_nav_mode_encode(target, nav_mode)) + + def param_request_read_encode(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value) + + def param_set_send(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value)) + + def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature)) + + def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def local_position_encode(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_message(usec, x, y, z, vx, vy, vz) + + def local_position_send(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz)) + + def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz) + + def global_position_send(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz)) + + def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop) + + def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)) + + def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def waypoint_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_request_message(target_system, target_component, seq) + + def waypoint_request_send(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_request_encode(target_system, target_component, seq)) + + def waypoint_set_current_encode(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_set_current_message(target_system, target_component, seq) + + def waypoint_set_current_send(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_set_current_encode(target_system, target_component, seq)) + + def waypoint_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_current_message(seq) + + def waypoint_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_current_encode(seq)) + + def waypoint_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_request_list_message(target_system, target_component) + + def waypoint_request_list_send(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_request_list_encode(target_system, target_component)) + + def waypoint_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return MAVLink_waypoint_count_message(target_system, target_component, count) + + def waypoint_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return self.send(self.waypoint_count_encode(target_system, target_component, count)) + + def waypoint_clear_all_encode(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_clear_all_message(target_system, target_component) + + def waypoint_clear_all_send(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_clear_all_encode(target_system, target_component)) + + def waypoint_reached_encode(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_reached_message(seq) + + def waypoint_reached_send(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_reached_encode(seq)) + + def waypoint_ack_encode(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return MAVLink_waypoint_ack_message(target_system, target_component, type) + + def waypoint_ack_send(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return self.send(self.waypoint_ack_encode(target_system, target_component, type)) + + def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude) + + def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude)) + + def gps_local_origin_set_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return MAVLink_gps_local_origin_set_message(latitude, longitude, altitude) + + def gps_local_origin_set_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude)) + + def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw) + + def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw)) + + def local_position_setpoint_encode(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_message(x, y, z, yaw) + + def local_position_setpoint_send(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_encode(x, y, z, yaw)) + + def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw) + + def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) + + def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) + + def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) + + def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) + + def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust) + + def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust)) + + def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust) + + def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def position_target_encode(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return MAVLink_position_target_message(x, y, z, yaw) + + def position_target_send(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return self.send(self.position_target_encode(x, y, z, yaw)) + + def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) + + def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) + + def set_altitude_encode(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return MAVLink_set_altitude_message(target, mode) + + def set_altitude_send(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return self.send(self.set_altitude_encode(target, mode)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode) + + def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)) + + def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) + + def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def global_position_int_encode(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz) + + def global_position_int_send(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4) + + def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance) + + def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance)) + + def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance) + + def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance)) + + def debug_vect_encode(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, usec, x, y, z) + + def debug_vect_send(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, usec, x, y, z)) + + def named_value_float_encode(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(name, value) + + def named_value_float_send(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(name, value)) + + def named_value_int_encode(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(name, value) + + def named_value_int_send(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(ind, value) + + def debug_send(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(ind, value)) + diff --git a/pymavlink/dialects/v09/ardupilotmega.xml b/pymavlink/dialects/v09/ardupilotmega.xml new file mode 100644 index 0000000..6733531 --- /dev/null +++ b/pymavlink/dialects/v09/ardupilotmega.xml @@ -0,0 +1,270 @@ + + + common.xml + + + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + + + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch(deg*100) or lat, depending on mount mode. + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + Empty + Empty + Empty + Empty + + + + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached minimum altitude + + + Breached fence boundary + + + + + + + Offsets and calibrations values for hardware + sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + + Configure on-board Camera Control System. + System ID + Component ID + Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + Exposure type enumeration from 1 to N (0 means ignore) + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + Control on-board Camera Control System to take shots. + System ID + Component ID + 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + 1 to N //Zoom's absolute position (0 means ignore) + -100 to 100 //Zooming step value to offset zoom from the current position + 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + 0: ignore, 1: shot or start filming + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + + Message to configure a camera mount, directional antenna, etc. + System ID + Component ID + mount operating mode (see MAV_MOUNT_MODE enum) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + + + + Message to control a camera mount, directional antenna, etc. + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + + + + Message with some status from APM to GCS about camera or antenna mount + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + + + + + A fence point. Used to set a point when from + GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 1, 0 is for return point) + total number of points (for sanity checking) + Latitude of point + Longitude of point + + + + Request a current fence point from MAV + System ID + Component ID + point index (first point is 1, 0 is for return point) + + + + Status of geo-fencing. Sent in extended + status stream when fencing enabled + 0 if currently inside fence, 1 if outside + number of fence breaches + last breach type (see FENCE_BREACH_* enum) + time of last breach in milliseconds since boot + + + + Status of DCM attitude estimator + X gyro drift estimate rad/s + Y gyro drift estimate rad/s + Z gyro drift estimate rad/s + average accel_weight + average renormalisation value + average error_roll_pitch value + average error_yaw value + + + + Status of simulation environment, if used + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + + + + Status of key hardware + board voltage (mV) + I2C error count + + + + Status generated by radio + local signal strength + remote signal strength + how full the tx buffer is as a percentage + background noise level + remote background noise level + receive errors + count of error corrected packets + + + diff --git a/pymavlink/dialects/v09/common.py b/pymavlink/dialects/v09/common.py new file mode 100644 index 0000000..b78412e --- /dev/null +++ b/pymavlink/dialects/v09/common.py @@ -0,0 +1,5131 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "0.9" +DIALECT = "common" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 85, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if False: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at waypoint (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this waypoint an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this waypoint an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this waypoint for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this waypoint for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this waypoint for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this waypoint for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Empty''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system to + # control the vehicle attitude and the + # attitude of various sensors such + # as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Empty''' +enums['MAV_CMD'][176].param[3] = '''Empty''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera capturing. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera capturing.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system + # to control the vehicle attitude and the + # attitude of various + # devices such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + ''') +enums['MAV_CMD'][201].param[1] = '''Region of interest mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple cameras etc.)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Empty''' +enums['MAV_CMD'][241].param[6] = '''Empty''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[3] = '''Reserved''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_ENUM_END = 246 # +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next waypoint. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next waypoint.''') +MAV_ROI_WPINDEX = 2 # Point toward given waypoint. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given waypoint.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_BOOT = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 3 +MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_ACTION_ACK = 9 +MAVLINK_MSG_ID_ACTION = 10 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_SET_NAV_MODE = 12 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_GPS_STATUS = 27 +MAVLINK_MSG_ID_RAW_IMU = 28 +MAVLINK_MSG_ID_RAW_PRESSURE = 29 +MAVLINK_MSG_ID_SCALED_PRESSURE = 38 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_LOCAL_POSITION = 31 +MAVLINK_MSG_ID_GLOBAL_POSITION = 33 +MAVLINK_MSG_ID_GPS_RAW = 32 +MAVLINK_MSG_ID_SYS_STATUS = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37 +MAVLINK_MSG_ID_WAYPOINT = 39 +MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40 +MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41 +MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42 +MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43 +MAVLINK_MSG_ID_WAYPOINT_COUNT = 44 +MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45 +MAVLINK_MSG_ID_WAYPOINT_REACHED = 46 +MAVLINK_MSG_ID_WAYPOINT_ACK = 47 +MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51 +MAVLINK_MSG_ID_CONTROL_STATUS = 52 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_POSITION_TARGET = 63 +MAVLINK_MSG_ID_STATE_CORRECTION = 64 +MAVLINK_MSG_ID_SET_ALTITUDE = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_HIL_STATE = 67 +MAVLINK_MSG_ID_HIL_CONTROLS = 68 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND = 75 +MAVLINK_MSG_ID_COMMAND_ACK = 76 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140 +MAVLINK_MSG_ID_DEBUG_VECT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 253 +MAVLINK_MSG_ID_STATUSTEXT = 254 +MAVLINK_MSG_ID_DEBUG = 255 + +class MAVLink_heartbeat_message(MAVLink_message): + ''' + The heartbeat message shows that a system is present and + responding. The type of the MAV and Autopilot hardware allow + the receiving system to treat further messages from this + system appropriate (e.g. by laying out the user interface + based on the autopilot). + ''' + id = MAVLINK_MSG_ID_HEARTBEAT + name = 'HEARTBEAT' + fieldnames = ['type', 'autopilot', 'mavlink_version'] + ordered_fieldnames = [ 'type', 'autopilot', 'mavlink_version' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 72 + + def __init__(self, type, autopilot, mavlink_version): + MAVLink_message.__init__(self, MAVLink_heartbeat_message.id, MAVLink_heartbeat_message.name) + self._fieldnames = MAVLink_heartbeat_message.fieldnames + self.type = type + self.autopilot = autopilot + self.mavlink_version = mavlink_version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) + +class MAVLink_boot_message(MAVLink_message): + ''' + The boot message indicates that a system is starting. The + onboard software version allows to keep track of onboard + soft/firmware revisions. + ''' + id = MAVLINK_MSG_ID_BOOT + name = 'BOOT' + fieldnames = ['version'] + ordered_fieldnames = [ 'version' ] + format = '>I' + native_format = bytearray('>I', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 39 + + def __init__(self, version): + MAVLink_message.__init__(self, MAVLink_boot_message.id, MAVLink_boot_message.name) + self._fieldnames = MAVLink_boot_message.fieldnames + self.version = version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version)) + +class MAVLink_system_time_message(MAVLink_message): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME + name = 'SYSTEM_TIME' + fieldnames = ['time_usec'] + ordered_fieldnames = [ 'time_usec' ] + format = '>Q' + native_format = bytearray('>Q', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 190 + + def __init__(self, time_usec): + MAVLink_message.__init__(self, MAVLink_system_time_message.id, MAVLink_system_time_message.name) + self._fieldnames = MAVLink_system_time_message.fieldnames + self.time_usec = time_usec + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec)) + +class MAVLink_ping_message(MAVLink_message): + ''' + A ping message either requesting or responding to a ping. This + allows to measure the system latencies, including serial port, + radio modem and UDP connections. + ''' + id = MAVLINK_MSG_ID_PING + name = 'PING' + fieldnames = ['seq', 'target_system', 'target_component', 'time'] + ordered_fieldnames = [ 'seq', 'target_system', 'target_component', 'time' ] + format = '>IBBQ' + native_format = bytearray('>IBBQ', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 92 + + def __init__(self, seq, target_system, target_component, time): + MAVLink_message.__init__(self, MAVLink_ping_message.id, MAVLink_ping_message.name) + self._fieldnames = MAVLink_ping_message.fieldnames + self.seq = seq + self.target_system = target_system + self.target_component = target_component + self.time = time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time)) + +class MAVLink_system_time_utc_message(MAVLink_message): + ''' + UTC date and time from GPS module + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME_UTC + name = 'SYSTEM_TIME_UTC' + fieldnames = ['utc_date', 'utc_time'] + ordered_fieldnames = [ 'utc_date', 'utc_time' ] + format = '>II' + native_format = bytearray('>II', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 191 + + def __init__(self, utc_date, utc_time): + MAVLink_message.__init__(self, MAVLink_system_time_utc_message.id, MAVLink_system_time_utc_message.name) + self._fieldnames = MAVLink_system_time_utc_message.fieldnames + self.utc_date = utc_date + self.utc_time = utc_time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time)) + +class MAVLink_change_operator_control_message(MAVLink_message): + ''' + Request to control this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL + name = 'CHANGE_OPERATOR_CONTROL' + fieldnames = ['target_system', 'control_request', 'version', 'passkey'] + ordered_fieldnames = [ 'target_system', 'control_request', 'version', 'passkey' ] + format = '>BBB25s' + native_format = bytearray('>BBBc', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 25] + crc_extra = 217 + + def __init__(self, target_system, control_request, version, passkey): + MAVLink_message.__init__(self, MAVLink_change_operator_control_message.id, MAVLink_change_operator_control_message.name) + self._fieldnames = MAVLink_change_operator_control_message.fieldnames + self.target_system = target_system + self.control_request = control_request + self.version = version + self.passkey = passkey + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey)) + +class MAVLink_change_operator_control_ack_message(MAVLink_message): + ''' + Accept / deny control of this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK + name = 'CHANGE_OPERATOR_CONTROL_ACK' + fieldnames = ['gcs_system_id', 'control_request', 'ack'] + ordered_fieldnames = [ 'gcs_system_id', 'control_request', 'ack' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 104 + + def __init__(self, gcs_system_id, control_request, ack): + MAVLink_message.__init__(self, MAVLink_change_operator_control_ack_message.id, MAVLink_change_operator_control_ack_message.name) + self._fieldnames = MAVLink_change_operator_control_ack_message.fieldnames + self.gcs_system_id = gcs_system_id + self.control_request = control_request + self.ack = ack + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack)) + +class MAVLink_auth_key_message(MAVLink_message): + ''' + Emit an encrypted signature / key identifying this system. + PLEASE NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for true + safety. + ''' + id = MAVLINK_MSG_ID_AUTH_KEY + name = 'AUTH_KEY' + fieldnames = ['key'] + ordered_fieldnames = [ 'key' ] + format = '>32s' + native_format = bytearray('>c', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [32] + crc_extra = 119 + + def __init__(self, key): + MAVLink_message.__init__(self, MAVLink_auth_key_message.id, MAVLink_auth_key_message.name) + self._fieldnames = MAVLink_auth_key_message.fieldnames + self.key = key + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key)) + +class MAVLink_action_ack_message(MAVLink_message): + ''' + This message acknowledges an action. IMPORTANT: The + acknowledgement can be also negative, e.g. the MAV rejects a + reset message because it is in-flight. The action ids are + defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION_ACK + name = 'ACTION_ACK' + fieldnames = ['action', 'result'] + ordered_fieldnames = [ 'action', 'result' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 219 + + def __init__(self, action, result): + MAVLink_message.__init__(self, MAVLink_action_ack_message.id, MAVLink_action_ack_message.name) + self._fieldnames = MAVLink_action_ack_message.fieldnames + self.action = action + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result)) + +class MAVLink_action_message(MAVLink_message): + ''' + An action message allows to execute a certain onboard action. + These include liftoff, land, storing parameters too EEPROM, + shutddown, etc. The action ids are defined in ENUM MAV_ACTION + in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION + name = 'ACTION' + fieldnames = ['target', 'target_component', 'action'] + ordered_fieldnames = [ 'target', 'target_component', 'action' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 60 + + def __init__(self, target, target_component, action): + MAVLink_message.__init__(self, MAVLink_action_message.id, MAVLink_action_message.name) + self._fieldnames = MAVLink_action_message.fieldnames + self.target = target + self.target_component = target_component + self.action = action + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action)) + +class MAVLink_set_mode_message(MAVLink_message): + ''' + Set the system mode, as defined by enum MAV_MODE in + mavlink/include/mavlink_types.h. There is no target component + id as the mode is by definition for the overall aircraft, not + only for one component. + ''' + id = MAVLINK_MSG_ID_SET_MODE + name = 'SET_MODE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 186 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_mode_message.id, MAVLink_set_mode_message.name) + self._fieldnames = MAVLink_set_mode_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode)) + +class MAVLink_set_nav_mode_message(MAVLink_message): + ''' + Set the system navigation mode, as defined by enum + MAV_NAV_MODE in mavlink/include/mavlink_types.h. The + navigation mode applies to the whole aircraft and thus all + components. + ''' + id = MAVLINK_MSG_ID_SET_NAV_MODE + name = 'SET_NAV_MODE' + fieldnames = ['target', 'nav_mode'] + ordered_fieldnames = [ 'target', 'nav_mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 10 + + def __init__(self, target, nav_mode): + MAVLink_message.__init__(self, MAVLink_set_nav_mode_message.id, MAVLink_set_nav_mode_message.name) + self._fieldnames = MAVLink_set_nav_mode_message.fieldnames + self.target = target + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode)) + +class MAVLink_param_request_read_message(MAVLink_message): + ''' + Request to read the onboard parameter with the param_id string + id. Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_index' ] + format = '>BB15bh' + native_format = bytearray('>BBbh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 89 + + def __init__(self, target_system, target_component, param_id, param_index): + MAVLink_message.__init__(self, MAVLink_param_request_read_message.id, MAVLink_param_request_read_message.name) + self._fieldnames = MAVLink_param_request_read_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15bh', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_index)) + +class MAVLink_param_request_list_message(MAVLink_message): + ''' + Request all parameters of this component. After his request, + all parameters are emitted. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_LIST + name = 'PARAM_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 159 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_param_request_list_message.id, MAVLink_param_request_list_message.name) + self._fieldnames = MAVLink_param_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_param_value_message(MAVLink_message): + ''' + Emit the value of a onboard parameter. The inclusion of + param_count and param_index in the message allows the + recipient to keep track of received parameters and allows him + to re-request missing parameters after a loss or timeout. + ''' + id = MAVLINK_MSG_ID_PARAM_VALUE + name = 'PARAM_VALUE' + fieldnames = ['param_id', 'param_value', 'param_count', 'param_index'] + ordered_fieldnames = [ 'param_id', 'param_value', 'param_count', 'param_index' ] + format = '>15bfHH' + native_format = bytearray('>bfHH', 'ascii') + orders = [0, 1, 2, 3] + lengths = [15, 1, 1, 1] + array_lengths = [15, 0, 0, 0] + crc_extra = 162 + + def __init__(self, param_id, param_value, param_count, param_index): + MAVLink_message.__init__(self, MAVLink_param_value_message.id, MAVLink_param_value_message.name) + self._fieldnames = MAVLink_param_value_message.fieldnames + self.param_id = param_id + self.param_value = param_value + self.param_count = param_count + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>15bfHH', self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value, self.param_count, self.param_index)) + +class MAVLink_param_set_message(MAVLink_message): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to + default on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents + to EEPROM. IMPORTANT: The receiving component should + acknowledge the new parameter value by sending a param_value + message to all communication partners. This will also ensure + that multiple GCS all have an up-to-date list of all + parameters. If the sending GCS did not receive a PARAM_VALUE + message within its timeout time, it should re-send the + PARAM_SET message. + ''' + id = MAVLINK_MSG_ID_PARAM_SET + name = 'PARAM_SET' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_value'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_value' ] + format = '>BB15bf' + native_format = bytearray('>BBbf', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 121 + + def __init__(self, target_system, target_component, param_id, param_value): + MAVLink_message.__init__(self, MAVLink_param_set_message.id, MAVLink_param_set_message.name) + self._fieldnames = MAVLink_param_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_value = param_value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15bf', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value)) + +class MAVLink_gps_raw_int_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW_INT + name = 'GPS_RAW_INT' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBiiiffff' + native_format = bytearray('>QBiiiffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 149 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_int_message.id, MAVLink_gps_raw_int_message.name) + self._fieldnames = MAVLink_gps_raw_int_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_scaled_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should contain the scaled values to the described + units + ''' + id = MAVLINK_MSG_ID_SCALED_IMU + name = 'SCALED_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 222 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_scaled_imu_message.id, MAVLink_scaled_imu_message.name) + self._fieldnames = MAVLink_scaled_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_gps_status_message(MAVLink_message): + ''' + The positioning status, as reported by GPS. This message is + intended to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION for the + global position estimate. This message can contain information + for up to 20 satellites. + ''' + id = MAVLINK_MSG_ID_GPS_STATUS + name = 'GPS_STATUS' + fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr'] + ordered_fieldnames = [ 'satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr' ] + format = '>B20b20b20b20b20b' + native_format = bytearray('>Bbbbbb', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 20, 20, 20, 20, 20] + array_lengths = [0, 20, 20, 20, 20, 20] + crc_extra = 110 + + def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + MAVLink_message.__init__(self, MAVLink_gps_status_message.id, MAVLink_gps_status_message.name) + self._fieldnames = MAVLink_gps_status_message.fieldnames + self.satellites_visible = satellites_visible + self.satellite_prn = satellite_prn + self.satellite_used = satellite_used + self.satellite_elevation = satellite_elevation + self.satellite_azimuth = satellite_azimuth + self.satellite_snr = satellite_snr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 110, struct.pack('>B20b20b20b20b20b', self.satellites_visible, self.satellite_prn[0], self.satellite_prn[1], self.satellite_prn[2], self.satellite_prn[3], self.satellite_prn[4], self.satellite_prn[5], self.satellite_prn[6], self.satellite_prn[7], self.satellite_prn[8], self.satellite_prn[9], self.satellite_prn[10], self.satellite_prn[11], self.satellite_prn[12], self.satellite_prn[13], self.satellite_prn[14], self.satellite_prn[15], self.satellite_prn[16], self.satellite_prn[17], self.satellite_prn[18], self.satellite_prn[19], self.satellite_used[0], self.satellite_used[1], self.satellite_used[2], self.satellite_used[3], self.satellite_used[4], self.satellite_used[5], self.satellite_used[6], self.satellite_used[7], self.satellite_used[8], self.satellite_used[9], self.satellite_used[10], self.satellite_used[11], self.satellite_used[12], self.satellite_used[13], self.satellite_used[14], self.satellite_used[15], self.satellite_used[16], self.satellite_used[17], self.satellite_used[18], self.satellite_used[19], self.satellite_elevation[0], self.satellite_elevation[1], self.satellite_elevation[2], self.satellite_elevation[3], self.satellite_elevation[4], self.satellite_elevation[5], self.satellite_elevation[6], self.satellite_elevation[7], self.satellite_elevation[8], self.satellite_elevation[9], self.satellite_elevation[10], self.satellite_elevation[11], self.satellite_elevation[12], self.satellite_elevation[13], self.satellite_elevation[14], self.satellite_elevation[15], self.satellite_elevation[16], self.satellite_elevation[17], self.satellite_elevation[18], self.satellite_elevation[19], self.satellite_azimuth[0], self.satellite_azimuth[1], self.satellite_azimuth[2], self.satellite_azimuth[3], self.satellite_azimuth[4], self.satellite_azimuth[5], self.satellite_azimuth[6], self.satellite_azimuth[7], self.satellite_azimuth[8], self.satellite_azimuth[9], self.satellite_azimuth[10], self.satellite_azimuth[11], self.satellite_azimuth[12], self.satellite_azimuth[13], self.satellite_azimuth[14], self.satellite_azimuth[15], self.satellite_azimuth[16], self.satellite_azimuth[17], self.satellite_azimuth[18], self.satellite_azimuth[19], self.satellite_snr[0], self.satellite_snr[1], self.satellite_snr[2], self.satellite_snr[3], self.satellite_snr[4], self.satellite_snr[5], self.satellite_snr[6], self.satellite_snr[7], self.satellite_snr[8], self.satellite_snr[9], self.satellite_snr[10], self.satellite_snr[11], self.satellite_snr[12], self.satellite_snr[13], self.satellite_snr[14], self.satellite_snr[15], self.satellite_snr[16], self.satellite_snr[17], self.satellite_snr[18], self.satellite_snr[19])) + +class MAVLink_raw_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should always contain the true raw values without any + scaling to allow data capture and system debugging. + ''' + id = MAVLINK_MSG_ID_RAW_IMU + name = 'RAW_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 179 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_raw_imu_message.id, MAVLink_raw_imu_message.name) + self._fieldnames = MAVLink_raw_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_raw_pressure_message(MAVLink_message): + ''' + The RAW pressure readings for the typical setup of one + absolute pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + ''' + id = MAVLINK_MSG_ID_RAW_PRESSURE + name = 'RAW_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature' ] + format = '>Qhhhh' + native_format = bytearray('>Qhhhh', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 136 + + def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature): + MAVLink_message.__init__(self, MAVLink_raw_pressure_message.id, MAVLink_raw_pressure_message.name) + self._fieldnames = MAVLink_raw_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff1 = press_diff1 + self.press_diff2 = press_diff2 + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature)) + +class MAVLink_scaled_pressure_message(MAVLink_message): + ''' + The pressure readings for the typical setup of one absolute + and differential pressure sensor. The units are as specified + in each field. + ''' + id = MAVLINK_MSG_ID_SCALED_PRESSURE + name = 'SCALED_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff', 'temperature' ] + format = '>Qffh' + native_format = bytearray('>Qffh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 229 + + def __init__(self, usec, press_abs, press_diff, temperature): + MAVLink_message.__init__(self, MAVLink_scaled_pressure_message.id, MAVLink_scaled_pressure_message.name) + self._fieldnames = MAVLink_scaled_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff = press_diff + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature)) + +class MAVLink_attitude_message(MAVLink_message): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, + X-front, Y-right). + ''' + id = MAVLINK_MSG_ID_ATTITUDE + name = 'ATTITUDE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 66 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + MAVLink_message.__init__(self, MAVLink_attitude_message.id, MAVLink_attitude_message.name) + self._fieldnames = MAVLink_attitude_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed)) + +class MAVLink_local_position_message(MAVLink_message): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, Z-axis down + (aeronautical frame) + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION + name = 'LOCAL_POSITION' + fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'x', 'y', 'z', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, usec, x, y, z, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_local_position_message.id, MAVLink_local_position_message.name) + self._fieldnames = MAVLink_local_position_message.fieldnames + self.usec = usec + self.x = x + self.y = y + self.z = z + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz)) + +class MAVLink_global_position_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). Coordinate frame is right-handed, Z-axis up + (GPS frame) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION + name = 'GLOBAL_POSITION' + fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 147 + + def __init__(self, usec, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_message.id, MAVLink_global_position_message.name) + self._fieldnames = MAVLink_global_position_message.fieldnames + self.usec = usec + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_gps_raw_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW + name = 'GPS_RAW' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBfffffff' + native_format = bytearray('>QBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 185 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_message.id, MAVLink_gps_raw_message.name) + self._fieldnames = MAVLink_gps_raw_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_sys_status_message(MAVLink_message): + ''' + The general system state. If the system is following the + MAVLink standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is either + LOCKED (motors shut down and locked), MANUAL (system under RC + control), GUIDED (system with autonomous position control, + position setpoint controlled manually) or AUTO (system guided + by path/waypoint planner). The NAV_MODE defined the current + flight state: LIFTOFF (often an open-loop maneuver), LANDING, + WAYPOINTS or VECTOR. This represents the internal navigation + state machine. The system status shows wether the system is + currently active or not and if an emergency occured. During + the CRITICAL and EMERGENCY states the MAV is still considered + to be active, but should start emergency procedures + autonomously. After a failure occured it should first move + from active to critical to allow manual intervention and then + move to emergency after a certain timeout. + ''' + id = MAVLINK_MSG_ID_SYS_STATUS + name = 'SYS_STATUS' + fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop'] + ordered_fieldnames = [ 'mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop' ] + format = '>BBBHHHH' + native_format = bytearray('>BBBHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 112 + + def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + MAVLink_message.__init__(self, MAVLink_sys_status_message.id, MAVLink_sys_status_message.name) + self._fieldnames = MAVLink_sys_status_message.fieldnames + self.mode = mode + self.nav_mode = nav_mode + self.status = status + self.load = load + self.vbat = vbat + self.battery_remaining = battery_remaining + self.packet_drop = packet_drop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop)) + +class MAVLink_rc_channels_raw_message(MAVLink_message): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_RAW + name = 'RC_CHANNELS_RAW' + fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi'] + ordered_fieldnames = [ 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi' ] + format = '>HHHHHHHHB' + native_format = bytearray('>HHHHHHHHB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 252 + + def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_raw_message.id, MAVLink_rc_channels_raw_message.name) + self._fieldnames = MAVLink_rc_channels_raw_message.fieldnames + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi)) + +class MAVLink_rc_channels_scaled_message(MAVLink_message): + ''' + The scaled values of the RC channels received. (-100%) -10000, + (0%) 0, (100%) 10000 + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_SCALED + name = 'RC_CHANNELS_SCALED' + fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi'] + ordered_fieldnames = [ 'chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi' ] + format = '>hhhhhhhhB' + native_format = bytearray('>hhhhhhhhB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 162 + + def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_scaled_message.id, MAVLink_rc_channels_scaled_message.name) + self._fieldnames = MAVLink_rc_channels_scaled_message.fieldnames + self.chan1_scaled = chan1_scaled + self.chan2_scaled = chan2_scaled + self.chan3_scaled = chan3_scaled + self.chan4_scaled = chan4_scaled + self.chan5_scaled = chan5_scaled + self.chan6_scaled = chan6_scaled + self.chan7_scaled = chan7_scaled + self.chan8_scaled = chan8_scaled + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi)) + +class MAVLink_servo_output_raw_message(MAVLink_message): + ''' + The RAW values of the servo outputs (for RC input from the + remote, use the RC_CHANNELS messages). The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + ''' + id = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW + name = 'SERVO_OUTPUT_RAW' + fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw'] + ordered_fieldnames = [ 'servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw' ] + format = '>HHHHHHHH' + native_format = bytearray('>HHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + MAVLink_message.__init__(self, MAVLink_servo_output_raw_message.id, MAVLink_servo_output_raw_message.name) + self._fieldnames = MAVLink_servo_output_raw_message.fieldnames + self.servo1_raw = servo1_raw + self.servo2_raw = servo2_raw + self.servo3_raw = servo3_raw + self.servo4_raw = servo4_raw + self.servo5_raw = servo5_raw + self.servo6_raw = servo6_raw + self.servo7_raw = servo7_raw + self.servo8_raw = servo8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw)) + +class MAVLink_waypoint_message(MAVLink_message): + ''' + Message encoding a waypoint. This message is emitted to + announce the presence of a waypoint and to set a waypoint + on the system. The waypoint can be either in x, y, z meters + (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is + Z-down, right handed, global frame is Z-up, right handed + ''' + id = MAVLINK_MSG_ID_WAYPOINT + name = 'WAYPOINT' + fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z' ] + format = '>BBHBBBBfffffff' + native_format = bytearray('>BBHBBBBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 128 + + def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + MAVLink_message.__init__(self, MAVLink_waypoint_message.id, MAVLink_waypoint_message.name) + self._fieldnames = MAVLink_waypoint_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + self.frame = frame + self.command = command + self.current = current + self.autocontinue = autocontinue + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z)) + +class MAVLink_waypoint_request_message(MAVLink_message): + ''' + Request the information of the waypoint with the sequence + number seq. The response of the system to this message should + be a WAYPOINT message. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST + name = 'WAYPOINT_REQUEST' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 9 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_request_message.id, MAVLink_waypoint_request_message.name) + self._fieldnames = MAVLink_waypoint_request_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_set_current_message(MAVLink_message): + ''' + Set the waypoint with sequence number seq as current waypoint. + This means that the MAV will continue to this waypoint on the + shortest path (not following the waypoints in-between). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT + name = 'WAYPOINT_SET_CURRENT' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 106 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_set_current_message.id, MAVLink_waypoint_set_current_message.name) + self._fieldnames = MAVLink_waypoint_set_current_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_current_message(MAVLink_message): + ''' + Message that announces the sequence number of the current + active waypoint. The MAV will fly towards this waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CURRENT + name = 'WAYPOINT_CURRENT' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 101 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_current_message.id, MAVLink_waypoint_current_message.name) + self._fieldnames = MAVLink_waypoint_current_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_request_list_message(MAVLink_message): + ''' + Request the overall list of waypoints from the + system/component. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST + name = 'WAYPOINT_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_request_list_message.id, MAVLink_waypoint_request_list_message.name) + self._fieldnames = MAVLink_waypoint_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_count_message(MAVLink_message): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST + by the MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of waypoints. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_COUNT + name = 'WAYPOINT_COUNT' + fieldnames = ['target_system', 'target_component', 'count'] + ordered_fieldnames = [ 'target_system', 'target_component', 'count' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 4 + + def __init__(self, target_system, target_component, count): + MAVLink_message.__init__(self, MAVLink_waypoint_count_message.id, MAVLink_waypoint_count_message.name) + self._fieldnames = MAVLink_waypoint_count_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.count = count + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count)) + +class MAVLink_waypoint_clear_all_message(MAVLink_message): + ''' + Delete all waypoints at once. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL + name = 'WAYPOINT_CLEAR_ALL' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 229 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_clear_all_message.id, MAVLink_waypoint_clear_all_message.name) + self._fieldnames = MAVLink_waypoint_clear_all_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_reached_message(MAVLink_message): + ''' + A certain waypoint has been reached. The system will either + hold this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REACHED + name = 'WAYPOINT_REACHED' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 21 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_reached_message.id, MAVLink_waypoint_reached_message.name) + self._fieldnames = MAVLink_waypoint_reached_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_ack_message(MAVLink_message): + ''' + Ack message during waypoint handling. The type field states if + this message is a positive ack (type=0) or if an error + happened (type=non-zero). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_ACK + name = 'WAYPOINT_ACK' + fieldnames = ['target_system', 'target_component', 'type'] + ordered_fieldnames = [ 'target_system', 'target_component', 'type' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 214 + + def __init__(self, target_system, target_component, type): + MAVLink_message.__init__(self, MAVLink_waypoint_ack_message.id, MAVLink_waypoint_ack_message.name) + self._fieldnames = MAVLink_waypoint_ack_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.type = type + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type)) + +class MAVLink_gps_set_global_origin_message(MAVLink_message): + ''' + As local waypoints exist, the global waypoint reference allows + to transform between the local coordinate frame and the global + (GPS) coordinate frame. This can be necessary when e.g. in- + and outdoor settings are connected and the MAV should move + from in- to outdoor. + ''' + id = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN + name = 'GPS_SET_GLOBAL_ORIGIN' + fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'target_system', 'target_component', 'latitude', 'longitude', 'altitude' ] + format = '>BBiii' + native_format = bytearray('>BBiii', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, target_system, target_component, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_set_global_origin_message.id, MAVLink_gps_set_global_origin_message.name) + self._fieldnames = MAVLink_gps_set_global_origin_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude)) + +class MAVLink_gps_local_origin_set_message(MAVLink_message): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + ''' + id = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET + name = 'GPS_LOCAL_ORIGIN_SET' + fieldnames = ['latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'latitude', 'longitude', 'altitude' ] + format = '>iii' + native_format = bytearray('>iii', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 14 + + def __init__(self, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_local_origin_set_message.id, MAVLink_gps_local_origin_set_message.name) + self._fieldnames = MAVLink_gps_local_origin_set_message.fieldnames + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude)) + +class MAVLink_local_position_setpoint_set_message(MAVLink_message): + ''' + Set the setpoint for a local position controller. This is the + position in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the onboard + position controller. As some MAVs have a degree of freedom in + yaw (e.g. all helicopters/quadrotors), the desired yaw angle + is part of the message. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET + name = 'LOCAL_POSITION_SETPOINT_SET' + fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'x', 'y', 'z', 'yaw' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 206 + + def __init__(self, target_system, target_component, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_set_message.id, MAVLink_local_position_setpoint_set_message.name) + self._fieldnames = MAVLink_local_position_setpoint_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw)) + +class MAVLink_local_position_setpoint_message(MAVLink_message): + ''' + Transmit the current local setpoint of the controller to other + MAVs (collision avoidance) and to the GCS. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT + name = 'LOCAL_POSITION_SETPOINT' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 50 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_message.id, MAVLink_local_position_setpoint_message.name) + self._fieldnames = MAVLink_local_position_setpoint_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_control_status_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_CONTROL_STATUS + name = 'CONTROL_STATUS' + fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw'] + ordered_fieldnames = [ 'position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw' ] + format = '>BBBBBBBB' + native_format = bytearray('>BBBBBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 157 + + def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + MAVLink_message.__init__(self, MAVLink_control_status_message.id, MAVLink_control_status_message.name) + self._fieldnames = MAVLink_control_status_message.fieldnames + self.position_fix = position_fix + self.vision_fix = vision_fix + self.gps_fix = gps_fix + self.ahrs_health = ahrs_health + self.control_att = control_att + self.control_pos_xy = control_pos_xy + self.control_pos_z = control_pos_z + self.control_pos_yaw = control_pos_yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw)) + +class MAVLink_safety_set_allowed_area_message(MAVLink_message): + ''' + Set a safety zone (volume), which is defined by two corners of + a cube. This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. Safety + areas are often enforced by national or competition + regulations. + ''' + id = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA + name = 'SAFETY_SET_ALLOWED_AREA' + fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>BBBffffff' + native_format = bytearray('>BBBffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_set_allowed_area_message.id, MAVLink_safety_set_allowed_area_message.name) + self._fieldnames = MAVLink_safety_set_allowed_area_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_safety_allowed_area_message(MAVLink_message): + ''' + Read out the safety zone the MAV currently assumes. + ''' + id = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA + name = 'SAFETY_ALLOWED_AREA' + fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>Bffffff' + native_format = bytearray('>Bffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 108 + + def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_allowed_area_message.id, MAVLink_safety_allowed_area_message.name) + self._fieldnames = MAVLink_safety_allowed_area_message.fieldnames + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST + name = 'SET_ROLL_PITCH_YAW_THRUST' + fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_thrust_message.id, MAVLink_set_roll_pitch_yaw_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST + name = 'SET_ROLL_PITCH_YAW_SPEED_THRUST' + fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 95 + + def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_speed_thrust_message.id, MAVLink_set_roll_pitch_yaw_speed_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_speed_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 5 + + def __init__(self, time_us, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active + on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 127 + + def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_nav_controller_output_message(MAVLink_message): + ''' + Outputs of the APM navigation controller. The primary use of + this message is to check the response and signs of the + controller before actual flight and to assist with tuning + controller parameters + ''' + id = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT + name = 'NAV_CONTROLLER_OUTPUT' + fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error'] + ordered_fieldnames = [ 'nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error' ] + format = '>ffhhHfff' + native_format = bytearray('>ffhhHfff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 57 + + def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + MAVLink_message.__init__(self, MAVLink_nav_controller_output_message.id, MAVLink_nav_controller_output_message.name) + self._fieldnames = MAVLink_nav_controller_output_message.fieldnames + self.nav_roll = nav_roll + self.nav_pitch = nav_pitch + self.nav_bearing = nav_bearing + self.target_bearing = target_bearing + self.wp_dist = wp_dist + self.alt_error = alt_error + self.aspd_error = aspd_error + self.xtrack_error = xtrack_error + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error)) + +class MAVLink_position_target_message(MAVLink_message): + ''' + The goal position of the system. This position is the input to + any navigation or path planning algorithm and does NOT + represent the current controller setpoint. + ''' + id = MAVLINK_MSG_ID_POSITION_TARGET + name = 'POSITION_TARGET' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_position_target_message.id, MAVLink_position_target_message.name) + self._fieldnames = MAVLink_position_target_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_state_correction_message(MAVLink_message): + ''' + Corrects the systems state by adding an error correction term + to the position and velocity, and by rotating the attitude by + a correction angle. + ''' + id = MAVLINK_MSG_ID_STATE_CORRECTION + name = 'STATE_CORRECTION' + fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr'] + ordered_fieldnames = [ 'xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr' ] + format = '>fffffffff' + native_format = bytearray('>fffffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 130 + + def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + MAVLink_message.__init__(self, MAVLink_state_correction_message.id, MAVLink_state_correction_message.name) + self._fieldnames = MAVLink_state_correction_message.fieldnames + self.xErr = xErr + self.yErr = yErr + self.zErr = zErr + self.rollErr = rollErr + self.pitchErr = pitchErr + self.yawErr = yawErr + self.vxErr = vxErr + self.vyErr = vyErr + self.vzErr = vzErr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr)) + +class MAVLink_set_altitude_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_SET_ALTITUDE + name = 'SET_ALTITUDE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BI' + native_format = bytearray('>BI', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 119 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_altitude_message.id, MAVLink_set_altitude_message.name) + self._fieldnames = MAVLink_set_altitude_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode)) + +class MAVLink_request_data_stream_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_REQUEST_DATA_STREAM + name = 'REQUEST_DATA_STREAM' + fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop'] + ordered_fieldnames = [ 'target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop' ] + format = '>BBBHB' + native_format = bytearray('>BBBHB', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 193 + + def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + MAVLink_message.__init__(self, MAVLink_request_data_stream_message.id, MAVLink_request_data_stream_message.name) + self._fieldnames = MAVLink_request_data_stream_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.req_stream_id = req_stream_id + self.req_message_rate = req_message_rate + self.start_stop = start_stop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop)) + +class MAVLink_hil_state_message(MAVLink_message): + ''' + This packet is useful for high throughput + applications such as hardware in the loop simulations. + ''' + id = MAVLINK_MSG_ID_HIL_STATE + name = 'HIL_STATE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc' ] + format = '>Qffffffiiihhhhhh' + native_format = bytearray('>Qffffffiiihhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 191 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + MAVLink_message.__init__(self, MAVLink_hil_state_message.id, MAVLink_hil_state_message.name) + self._fieldnames = MAVLink_hil_state_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc)) + +class MAVLink_hil_controls_message(MAVLink_message): + ''' + Hardware in the loop control outputs + ''' + id = MAVLINK_MSG_ID_HIL_CONTROLS + name = 'HIL_CONTROLS' + fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode'] + ordered_fieldnames = [ 'time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode' ] + format = '>QffffBB' + native_format = bytearray('>QffffBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 236 + + def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + MAVLink_message.__init__(self, MAVLink_hil_controls_message.id, MAVLink_hil_controls_message.name) + self._fieldnames = MAVLink_hil_controls_message.fieldnames + self.time_us = time_us + self.roll_ailerons = roll_ailerons + self.pitch_elevator = pitch_elevator + self.yaw_rudder = yaw_rudder + self.throttle = throttle + self.mode = mode + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode)) + +class MAVLink_manual_control_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_MANUAL_CONTROL + name = 'MANUAL_CONTROL' + fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual'] + ordered_fieldnames = [ 'target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual' ] + format = '>BffffBBBB' + native_format = bytearray('>BffffBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 158 + + def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + MAVLink_message.__init__(self, MAVLink_manual_control_message.id, MAVLink_manual_control_message.name) + self._fieldnames = MAVLink_manual_control_message.fieldnames + self.target = target + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + self.roll_manual = roll_manual + self.pitch_manual = pitch_manual + self.yaw_manual = yaw_manual + self.thrust_manual = thrust_manual + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual)) + +class MAVLink_rc_channels_override_message(MAVLink_message): + ''' + The RAW values of the RC channels sent to the MAV to override + info received from the RC radio. A value of -1 means no change + to that channel. A value of 0 means control of that channel + should be released back to the RC radio. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE + name = 'RC_CHANNELS_OVERRIDE' + fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw' ] + format = '>BBHHHHHHHH' + native_format = bytearray('>BBHHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 143 + + def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + MAVLink_message.__init__(self, MAVLink_rc_channels_override_message.id, MAVLink_rc_channels_override_message.name) + self._fieldnames = MAVLink_rc_channels_override_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw)) + +class MAVLink_global_position_int_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). The position is in GPS-frame (right-handed, + Z-up) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION_INT + name = 'GLOBAL_POSITION_INT' + fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>iiihhh' + native_format = bytearray('>iiihhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 104 + + def __init__(self, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_int_message.id, MAVLink_global_position_int_message.name) + self._fieldnames = MAVLink_global_position_int_message.fieldnames + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_vfr_hud_message(MAVLink_message): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + ''' + id = MAVLINK_MSG_ID_VFR_HUD + name = 'VFR_HUD' + fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb'] + ordered_fieldnames = [ 'airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb' ] + format = '>ffhHff' + native_format = bytearray('>ffhHff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 123 + + def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb): + MAVLink_message.__init__(self, MAVLink_vfr_hud_message.id, MAVLink_vfr_hud_message.name) + self._fieldnames = MAVLink_vfr_hud_message.fieldnames + self.airspeed = airspeed + self.groundspeed = groundspeed + self.heading = heading + self.throttle = throttle + self.alt = alt + self.climb = climb + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb)) + +class MAVLink_command_message(MAVLink_message): + ''' + Send a command with up to four parameters to the MAV + ''' + id = MAVLINK_MSG_ID_COMMAND + name = 'COMMAND' + fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4'] + ordered_fieldnames = [ 'target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4' ] + format = '>BBBBffff' + native_format = bytearray('>BBBBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 131 + + def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + MAVLink_message.__init__(self, MAVLink_command_message.id, MAVLink_command_message.name) + self._fieldnames = MAVLink_command_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.command = command + self.confirmation = confirmation + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4)) + +class MAVLink_command_ack_message(MAVLink_message): + ''' + Report status of a command. Includes feedback wether the + command was executed + ''' + id = MAVLINK_MSG_ID_COMMAND_ACK + name = 'COMMAND_ACK' + fieldnames = ['command', 'result'] + ordered_fieldnames = [ 'command', 'result' ] + format = '>ff' + native_format = bytearray('>ff', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 8 + + def __init__(self, command, result): + MAVLink_message.__init__(self, MAVLink_command_ack_message.id, MAVLink_command_ack_message.name) + self._fieldnames = MAVLink_command_ack_message.fieldnames + self.command = command + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result)) + +class MAVLink_optical_flow_message(MAVLink_message): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + ''' + id = MAVLINK_MSG_ID_OPTICAL_FLOW + name = 'OPTICAL_FLOW' + fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance'] + ordered_fieldnames = [ 'time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance' ] + format = '>QBhhBf' + native_format = bytearray('>QBhhBf', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 174 + + def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + MAVLink_message.__init__(self, MAVLink_optical_flow_message.id, MAVLink_optical_flow_message.name) + self._fieldnames = MAVLink_optical_flow_message.fieldnames + self.time = time + self.sensor_id = sensor_id + self.flow_x = flow_x + self.flow_y = flow_y + self.quality = quality + self.ground_distance = ground_distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance)) + +class MAVLink_object_detection_event_message(MAVLink_message): + ''' + Object has been detected + ''' + id = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT + name = 'OBJECT_DETECTION_EVENT' + fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance'] + ordered_fieldnames = [ 'time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance' ] + format = '>IHB20sBff' + native_format = bytearray('>IHBcBff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 20, 0, 0, 0] + crc_extra = 155 + + def __init__(self, time, object_id, type, name, quality, bearing, distance): + MAVLink_message.__init__(self, MAVLink_object_detection_event_message.id, MAVLink_object_detection_event_message.name) + self._fieldnames = MAVLink_object_detection_event_message.fieldnames + self.time = time + self.object_id = object_id + self.type = type + self.name = name + self.quality = quality + self.bearing = bearing + self.distance = distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance)) + +class MAVLink_debug_vect_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_DEBUG_VECT + name = 'DEBUG_VECT' + fieldnames = ['name', 'usec', 'x', 'y', 'z'] + ordered_fieldnames = [ 'name', 'usec', 'x', 'y', 'z' ] + format = '>10sQfff' + native_format = bytearray('>cQfff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [10, 0, 0, 0, 0] + crc_extra = 178 + + def __init__(self, name, usec, x, y, z): + MAVLink_message.__init__(self, MAVLink_debug_vect_message.id, MAVLink_debug_vect_message.name) + self._fieldnames = MAVLink_debug_vect_message.fieldnames + self.name = name + self.usec = usec + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z)) + +class MAVLink_named_value_float_message(MAVLink_message): + ''' + Send a key-value pair as float. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT + name = 'NAMED_VALUE_FLOAT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10sf' + native_format = bytearray('>cf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 224 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_float_message.id, MAVLink_named_value_float_message.name) + self._fieldnames = MAVLink_named_value_float_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value)) + +class MAVLink_named_value_int_message(MAVLink_message): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_INT + name = 'NAMED_VALUE_INT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10si' + native_format = bytearray('>ci', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 60 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_int_message.id, MAVLink_named_value_int_message.name) + self._fieldnames = MAVLink_named_value_int_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value)) + +class MAVLink_statustext_message(MAVLink_message): + ''' + Status text message. These messages are printed in yellow in + the COMM console of QGroundControl. WARNING: They consume + quite some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages are + buffered on the MCU and sent only at a limited rate (e.g. 10 + Hz). + ''' + id = MAVLINK_MSG_ID_STATUSTEXT + name = 'STATUSTEXT' + fieldnames = ['severity', 'text'] + ordered_fieldnames = [ 'severity', 'text' ] + format = '>B50b' + native_format = bytearray('>Bb', 'ascii') + orders = [0, 1] + lengths = [1, 50] + array_lengths = [0, 50] + crc_extra = 106 + + def __init__(self, severity, text): + MAVLink_message.__init__(self, MAVLink_statustext_message.id, MAVLink_statustext_message.name) + self._fieldnames = MAVLink_statustext_message.fieldnames + self.severity = severity + self.text = text + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>B50b', self.severity, self.text[0], self.text[1], self.text[2], self.text[3], self.text[4], self.text[5], self.text[6], self.text[7], self.text[8], self.text[9], self.text[10], self.text[11], self.text[12], self.text[13], self.text[14], self.text[15], self.text[16], self.text[17], self.text[18], self.text[19], self.text[20], self.text[21], self.text[22], self.text[23], self.text[24], self.text[25], self.text[26], self.text[27], self.text[28], self.text[29], self.text[30], self.text[31], self.text[32], self.text[33], self.text[34], self.text[35], self.text[36], self.text[37], self.text[38], self.text[39], self.text[40], self.text[41], self.text[42], self.text[43], self.text[44], self.text[45], self.text[46], self.text[47], self.text[48], self.text[49])) + +class MAVLink_debug_message(MAVLink_message): + ''' + Send a debug value. The index is used to discriminate between + values. These values show up in the plot of QGroundControl as + DEBUG N. + ''' + id = MAVLINK_MSG_ID_DEBUG + name = 'DEBUG' + fieldnames = ['ind', 'value'] + ordered_fieldnames = [ 'ind', 'value' ] + format = '>Bf' + native_format = bytearray('>Bf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 7 + + def __init__(self, ind, value): + MAVLink_message.__init__(self, MAVLink_debug_message.id, MAVLink_debug_message.name) + self._fieldnames = MAVLink_debug_message.fieldnames + self.ind = ind + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value)) + + +mavlink_map = { + MAVLINK_MSG_ID_HEARTBEAT : MAVLink_heartbeat_message, + MAVLINK_MSG_ID_BOOT : MAVLink_boot_message, + MAVLINK_MSG_ID_SYSTEM_TIME : MAVLink_system_time_message, + MAVLINK_MSG_ID_PING : MAVLink_ping_message, + MAVLINK_MSG_ID_SYSTEM_TIME_UTC : MAVLink_system_time_utc_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : MAVLink_change_operator_control_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : MAVLink_change_operator_control_ack_message, + MAVLINK_MSG_ID_AUTH_KEY : MAVLink_auth_key_message, + MAVLINK_MSG_ID_ACTION_ACK : MAVLink_action_ack_message, + MAVLINK_MSG_ID_ACTION : MAVLink_action_message, + MAVLINK_MSG_ID_SET_MODE : MAVLink_set_mode_message, + MAVLINK_MSG_ID_SET_NAV_MODE : MAVLink_set_nav_mode_message, + MAVLINK_MSG_ID_PARAM_REQUEST_READ : MAVLink_param_request_read_message, + MAVLINK_MSG_ID_PARAM_REQUEST_LIST : MAVLink_param_request_list_message, + MAVLINK_MSG_ID_PARAM_VALUE : MAVLink_param_value_message, + MAVLINK_MSG_ID_PARAM_SET : MAVLink_param_set_message, + MAVLINK_MSG_ID_GPS_RAW_INT : MAVLink_gps_raw_int_message, + MAVLINK_MSG_ID_SCALED_IMU : MAVLink_scaled_imu_message, + MAVLINK_MSG_ID_GPS_STATUS : MAVLink_gps_status_message, + MAVLINK_MSG_ID_RAW_IMU : MAVLink_raw_imu_message, + MAVLINK_MSG_ID_RAW_PRESSURE : MAVLink_raw_pressure_message, + MAVLINK_MSG_ID_SCALED_PRESSURE : MAVLink_scaled_pressure_message, + MAVLINK_MSG_ID_ATTITUDE : MAVLink_attitude_message, + MAVLINK_MSG_ID_LOCAL_POSITION : MAVLink_local_position_message, + MAVLINK_MSG_ID_GLOBAL_POSITION : MAVLink_global_position_message, + MAVLINK_MSG_ID_GPS_RAW : MAVLink_gps_raw_message, + MAVLINK_MSG_ID_SYS_STATUS : MAVLink_sys_status_message, + MAVLINK_MSG_ID_RC_CHANNELS_RAW : MAVLink_rc_channels_raw_message, + MAVLINK_MSG_ID_RC_CHANNELS_SCALED : MAVLink_rc_channels_scaled_message, + MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : MAVLink_servo_output_raw_message, + MAVLINK_MSG_ID_WAYPOINT : MAVLink_waypoint_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST : MAVLink_waypoint_request_message, + MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : MAVLink_waypoint_set_current_message, + MAVLINK_MSG_ID_WAYPOINT_CURRENT : MAVLink_waypoint_current_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : MAVLink_waypoint_request_list_message, + MAVLINK_MSG_ID_WAYPOINT_COUNT : MAVLink_waypoint_count_message, + MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : MAVLink_waypoint_clear_all_message, + MAVLINK_MSG_ID_WAYPOINT_REACHED : MAVLink_waypoint_reached_message, + MAVLINK_MSG_ID_WAYPOINT_ACK : MAVLink_waypoint_ack_message, + MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : MAVLink_gps_set_global_origin_message, + MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : MAVLink_gps_local_origin_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : MAVLink_local_position_setpoint_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : MAVLink_local_position_setpoint_message, + MAVLINK_MSG_ID_CONTROL_STATUS : MAVLink_control_status_message, + MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : MAVLink_safety_set_allowed_area_message, + MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : MAVLink_safety_allowed_area_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : MAVLink_set_roll_pitch_yaw_thrust_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : MAVLink_set_roll_pitch_yaw_speed_thrust_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_thrust_setpoint_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, + MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : MAVLink_nav_controller_output_message, + MAVLINK_MSG_ID_POSITION_TARGET : MAVLink_position_target_message, + MAVLINK_MSG_ID_STATE_CORRECTION : MAVLink_state_correction_message, + MAVLINK_MSG_ID_SET_ALTITUDE : MAVLink_set_altitude_message, + MAVLINK_MSG_ID_REQUEST_DATA_STREAM : MAVLink_request_data_stream_message, + MAVLINK_MSG_ID_HIL_STATE : MAVLink_hil_state_message, + MAVLINK_MSG_ID_HIL_CONTROLS : MAVLink_hil_controls_message, + MAVLINK_MSG_ID_MANUAL_CONTROL : MAVLink_manual_control_message, + MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : MAVLink_rc_channels_override_message, + MAVLINK_MSG_ID_GLOBAL_POSITION_INT : MAVLink_global_position_int_message, + MAVLINK_MSG_ID_VFR_HUD : MAVLink_vfr_hud_message, + MAVLINK_MSG_ID_COMMAND : MAVLink_command_message, + MAVLINK_MSG_ID_COMMAND_ACK : MAVLink_command_ack_message, + MAVLINK_MSG_ID_OPTICAL_FLOW : MAVLink_optical_flow_message, + MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : MAVLink_object_detection_event_message, + MAVLINK_MSG_ID_DEBUG_VECT : MAVLink_debug_vect_message, + MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : MAVLink_named_value_float_message, + MAVLINK_MSG_ID_NAMED_VALUE_INT : MAVLink_named_value_int_message, + MAVLINK_MSG_ID_STATUSTEXT : MAVLink_statustext_message, + MAVLINK_MSG_ID_DEBUG : MAVLink_debug_message, +} + +class MAVError(Exception): + '''MAVLink error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + +class MAVString(str): + '''NUL terminated string''' + def __init__(self, s): + str.__init__(self) + def __str__(self): + i = self.find(chr(0)) + if i == -1: + return self[:] + return self[0:i] + +class MAVLink_bad_data(MAVLink_message): + ''' + a piece of bad data in a mavlink stream + ''' + def __init__(self, data, reason): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') + self._fieldnames = ['data', 'reason'] + self.data = data + self.reason = reason + self._msgbuf = data + + def __str__(self): + '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' + return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) + +class MAVLink(object): + '''MAVLink protocol handling class''' + def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): + self.seq = 0 + self.file = file + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.callback = None + self.callback_args = None + self.callback_kwargs = None + self.send_callback = None + self.send_callback_args = None + self.send_callback_kwargs = None + self.buf = bytearray() + self.expected_length = 8 + self.have_prefix_error = False + self.robust_parsing = False + self.protocol_marker = 85 + self.little_endian = False + self.crc_extra = False + self.sort_fields = False + self.total_packets_sent = 0 + self.total_bytes_sent = 0 + self.total_packets_received = 0 + self.total_bytes_received = 0 + self.total_receive_errors = 0 + self.startup_time = time.time() + if native_supported and (use_native or native_testing or native_force): + print("NOTE: mavnative is currently beta-test code") + self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) + else: + self.native = None + if native_testing: + self.test_buf = bytearray() + + def set_callback(self, callback, *args, **kwargs): + self.callback = callback + self.callback_args = args + self.callback_kwargs = kwargs + + def set_send_callback(self, callback, *args, **kwargs): + self.send_callback = callback + self.send_callback_args = args + self.send_callback_kwargs = kwargs + + def send(self, mavmsg): + '''send a MAVLink message''' + buf = mavmsg.pack(self) + self.file.write(buf) + self.seq = (self.seq + 1) % 256 + self.total_packets_sent += 1 + self.total_bytes_sent += len(buf) + if self.send_callback: + self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) + + def bytes_needed(self): + '''return number of bytes needed for next parsing stage''' + if self.native: + ret = self.native.expected_length - len(self.buf) + else: + ret = self.expected_length - len(self.buf) + + if ret <= 0: + return 1 + return ret + + def __parse_char_native(self, c): + '''this method exists only to see in profiling results''' + m = self.native.parse_chars(c) + return m + + def __callbacks(self, msg): + '''this method exists only to make profiling results easier to read''' + if self.callback: + self.callback(msg, *self.callback_args, **self.callback_kwargs) + + def parse_char(self, c): + '''input some data bytes, possibly returning a new message''' + self.buf.extend(c) + + self.total_bytes_received += len(c) + + if self.native: + if native_testing: + self.test_buf.extend(c) + m = self.__parse_char_native(self.test_buf) + m2 = self.__parse_char_legacy() + if m2 != m: + print("Native: %s\nLegacy: %s\n" % (m, m2)) + raise Exception('Native vs. Legacy mismatch') + else: + m = self.__parse_char_native(self.buf) + else: + m = self.__parse_char_legacy() + + if m != None: + self.total_packets_received += 1 + self.__callbacks(m) + + return m + + def __parse_char_legacy(self): + '''input some data bytes, possibly returning a new message (uses no native code)''' + if len(self.buf) >= 1 and self.buf[0] != 85: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 85: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value) + + def param_set_send(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value)) + + def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature)) + + def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def local_position_encode(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_message(usec, x, y, z, vx, vy, vz) + + def local_position_send(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz)) + + def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz) + + def global_position_send(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz)) + + def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop) + + def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)) + + def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def waypoint_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_request_message(target_system, target_component, seq) + + def waypoint_request_send(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_request_encode(target_system, target_component, seq)) + + def waypoint_set_current_encode(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_set_current_message(target_system, target_component, seq) + + def waypoint_set_current_send(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_set_current_encode(target_system, target_component, seq)) + + def waypoint_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_current_message(seq) + + def waypoint_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_current_encode(seq)) + + def waypoint_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_request_list_message(target_system, target_component) + + def waypoint_request_list_send(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_request_list_encode(target_system, target_component)) + + def waypoint_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return MAVLink_waypoint_count_message(target_system, target_component, count) + + def waypoint_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return self.send(self.waypoint_count_encode(target_system, target_component, count)) + + def waypoint_clear_all_encode(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_clear_all_message(target_system, target_component) + + def waypoint_clear_all_send(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_clear_all_encode(target_system, target_component)) + + def waypoint_reached_encode(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_reached_message(seq) + + def waypoint_reached_send(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_reached_encode(seq)) + + def waypoint_ack_encode(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return MAVLink_waypoint_ack_message(target_system, target_component, type) + + def waypoint_ack_send(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return self.send(self.waypoint_ack_encode(target_system, target_component, type)) + + def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude) + + def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude)) + + def gps_local_origin_set_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return MAVLink_gps_local_origin_set_message(latitude, longitude, altitude) + + def gps_local_origin_set_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude)) + + def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw) + + def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw)) + + def local_position_setpoint_encode(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_message(x, y, z, yaw) + + def local_position_setpoint_send(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_encode(x, y, z, yaw)) + + def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw) + + def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) + + def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) + + def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) + + def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) + + def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust) + + def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust)) + + def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust) + + def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def position_target_encode(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return MAVLink_position_target_message(x, y, z, yaw) + + def position_target_send(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return self.send(self.position_target_encode(x, y, z, yaw)) + + def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) + + def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) + + def set_altitude_encode(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return MAVLink_set_altitude_message(target, mode) + + def set_altitude_send(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return self.send(self.set_altitude_encode(target, mode)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode) + + def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)) + + def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) + + def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def global_position_int_encode(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz) + + def global_position_int_send(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4) + + def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance) + + def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance)) + + def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance) + + def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance)) + + def debug_vect_encode(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, usec, x, y, z) + + def debug_vect_send(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, usec, x, y, z)) + + def named_value_float_encode(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(name, value) + + def named_value_float_send(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(name, value)) + + def named_value_int_encode(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(name, value) + + def named_value_int_send(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(ind, value) + + def debug_send(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(ind, value)) + diff --git a/pymavlink/dialects/v09/common.xml b/pymavlink/dialects/v09/common.xml new file mode 100644 index 0000000..dd4ea84 --- /dev/null +++ b/pymavlink/dialects/v09/common.xml @@ -0,0 +1,941 @@ + + + 2 + + + Commands to be executed by the MAV. They can be executed on user request, + or as part of a mission script. If the action is used in a mission, the parameter mapping + to the waypoint/mission message is as follows: + Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what + ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to waypoint. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at waypoint (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this waypoint an unlimited amount of time + Empty + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X turns + Turns + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X seconds + Seconds (decimal) + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Empty + Empty + Empty + Desired yaw angle. + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Empty + Empty + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + Empty + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Control onboard camera capturing. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + + Region of interest mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple cameras etc.) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Empty + Empty + Empty + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Reserved + Reserved + Empty + Empty + Empty + + + + Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + + No region of interest. + + + Point toward next waypoint. + + + Point toward given waypoint. + + + Point toward fixed location. + + + Point toward of given id. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. + The onboard software version + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + Unix timestamp in microseconds + + + UTC date and time from GPS module + GPS UTC date ddmmyy + GPS UTC time hhmmss + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The action id + 0: Action DENIED, 1: Action executed + + + An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The system executing the action + The component executing the action + The action id + + + Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new mode + + + Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components. + The system setting the mode + The new navigation mode + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id + Parameter index. Send -1 to use the param ID field as identifier + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id + Onboard parameter value + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id + Onboard parameter value + + + The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in 1E7 degrees + Longitude in 1E7 degrees + Altitude in 1E3 meters (millimeters) + GPS HDOP + GPS VDOP + GPS ground speed (m/s) + Compass heading in degrees, 0..360 degrees + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw) + Differential pressure 2 (raw) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since unix epoch) + Latitude, in degrees + Longitude, in degrees + Absolute altitude, in meters + X Speed (in Latitude direction, positive: going north) + Y Speed (in Longitude direction, positive: going east) + Z Speed (in Altitude direction, positive: going up) + + + The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in degrees + Longitude in degrees + Altitude in meters + GPS HDOP + GPS VDOP + GPS ground speed + Compass heading in degrees, 0..360 degrees + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + Navigation mode, see MAV_NAV_MODE ENUM + System status flag, see MAV_STATUS ENUM + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Remaining battery energy: (0%: 0, 100%: 1000) + Dropped packets (packets that were corrupted on reception on the MAV) + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + Receive signal strength indicator, 0: 0%, 255: 100% + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed + System ID + Component ID + Sequence + The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude + + + Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message. + System ID + Component ID + Sequence + + + Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint. + Sequence + + + Request the overall list of waypoints from the system/component. + System ID + Component ID + + + This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints. + System ID + Component ID + Number of Waypoints in the Sequence + + + Delete all waypoints at once. + System ID + Component ID + + + A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. + Sequence + + + Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + 0: OK, 1: Error + + + As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Component ID + global position * 1E7 + global position * 1E7 + global position * 1000 + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), expressed as * 1E7 + Longitude (WGS84), expressed as * 1E7 + Altitude(WGS84), expressed as * 1000 + + + Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. + System ID + Component ID + x position + y position + z position + Desired yaw angle + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + x position + y position + z position + Desired yaw angle + + + Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + Attitude estimation health: 0: poor, 255: excellent + 0: Attitude control disabled, 1: enabled + 0: X, Y position control disabled, 1: enabled + 0: Z position control disabled, 1: enabled + 0: Yaw angle control disabled, 1: enabled + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + Collective thrust, normalized to 0 .. 1 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + Collective thrust, normalized to 0 .. 1 + + + Setpoint in roll, pitch, yaw currently active on the system. + Timestamp in micro seconds since unix epoch + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + Collective thrust, normalized to 0 .. 1 + + + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system. + Timestamp in micro seconds since unix epoch + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + Collective thrust, normalized to 0 .. 1 + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs +of the controller before actual flight and to assist with tuning controller parameters + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current waypoint/target in degrees + Distance to active waypoint in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint. + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. + x position error + y position error + z position error + roll error (radians) + pitch error (radians) + yaw error (radians) + x velocity + y velocity + z velocity + + + The system setting the altitude + The new altitude in meters + + + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested message type + Update rate in Hertz + 1 to start sending, 0 to stop sending. + + + This packet is useful for high throughput + applications such as hardware in the loop simulations. + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -3 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Send a command with up to four parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed + Current airspeed in m/s + 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels in x-sensor direction + Flow in pixels in y-sensor direction + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters + + + Object has been detected + Timestamp in milliseconds since system boot + Object ID + Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal + Name of the object as defined by the detector + Detection quality / confidence. 0: bad, 255: maximum confidence + Angle of the object with respect to the body frame in NED coordinates in radians. 0: front + Ground distance in meters + + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status, 0 = info message, 255 = critical fault + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + index of debug variable + DEBUG value + + + diff --git a/pymavlink/dialects/v09/minimal.py b/pymavlink/dialects/v09/minimal.py new file mode 100644 index 0000000..d7d0867 --- /dev/null +++ b/pymavlink/dialects/v09/minimal.py @@ -0,0 +1,491 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: minimal.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "0.9" +DIALECT = "minimal" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 85, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if False: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack('BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 72 + + def __init__(self, type, autopilot, mavlink_version): + MAVLink_message.__init__(self, MAVLink_heartbeat_message.id, MAVLink_heartbeat_message.name) + self._fieldnames = MAVLink_heartbeat_message.fieldnames + self.type = type + self.autopilot = autopilot + self.mavlink_version = mavlink_version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) + + +mavlink_map = { + MAVLINK_MSG_ID_HEARTBEAT : MAVLink_heartbeat_message, +} + +class MAVError(Exception): + '''MAVLink error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + +class MAVString(str): + '''NUL terminated string''' + def __init__(self, s): + str.__init__(self) + def __str__(self): + i = self.find(chr(0)) + if i == -1: + return self[:] + return self[0:i] + +class MAVLink_bad_data(MAVLink_message): + ''' + a piece of bad data in a mavlink stream + ''' + def __init__(self, data, reason): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') + self._fieldnames = ['data', 'reason'] + self.data = data + self.reason = reason + self._msgbuf = data + + def __str__(self): + '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' + return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) + +class MAVLink(object): + '''MAVLink protocol handling class''' + def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): + self.seq = 0 + self.file = file + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.callback = None + self.callback_args = None + self.callback_kwargs = None + self.send_callback = None + self.send_callback_args = None + self.send_callback_kwargs = None + self.buf = bytearray() + self.expected_length = 8 + self.have_prefix_error = False + self.robust_parsing = False + self.protocol_marker = 85 + self.little_endian = False + self.crc_extra = False + self.sort_fields = False + self.total_packets_sent = 0 + self.total_bytes_sent = 0 + self.total_packets_received = 0 + self.total_bytes_received = 0 + self.total_receive_errors = 0 + self.startup_time = time.time() + if native_supported and (use_native or native_testing or native_force): + print("NOTE: mavnative is currently beta-test code") + self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) + else: + self.native = None + if native_testing: + self.test_buf = bytearray() + + def set_callback(self, callback, *args, **kwargs): + self.callback = callback + self.callback_args = args + self.callback_kwargs = kwargs + + def set_send_callback(self, callback, *args, **kwargs): + self.send_callback = callback + self.send_callback_args = args + self.send_callback_kwargs = kwargs + + def send(self, mavmsg): + '''send a MAVLink message''' + buf = mavmsg.pack(self) + self.file.write(buf) + self.seq = (self.seq + 1) % 256 + self.total_packets_sent += 1 + self.total_bytes_sent += len(buf) + if self.send_callback: + self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) + + def bytes_needed(self): + '''return number of bytes needed for next parsing stage''' + if self.native: + ret = self.native.expected_length - len(self.buf) + else: + ret = self.expected_length - len(self.buf) + + if ret <= 0: + return 1 + return ret + + def __parse_char_native(self, c): + '''this method exists only to see in profiling results''' + m = self.native.parse_chars(c) + return m + + def __callbacks(self, msg): + '''this method exists only to make profiling results easier to read''' + if self.callback: + self.callback(msg, *self.callback_args, **self.callback_kwargs) + + def parse_char(self, c): + '''input some data bytes, possibly returning a new message''' + self.buf.extend(c) + + self.total_bytes_received += len(c) + + if self.native: + if native_testing: + self.test_buf.extend(c) + m = self.__parse_char_native(self.test_buf) + m2 = self.__parse_char_legacy() + if m2 != m: + print("Native: %s\nLegacy: %s\n" % (m, m2)) + raise Exception('Native vs. Legacy mismatch') + else: + m = self.__parse_char_native(self.buf) + else: + m = self.__parse_char_legacy() + + if m != None: + self.total_packets_received += 1 + self.__callbacks(m) + + return m + + def __parse_char_legacy(self): + '''input some data bytes, possibly returning a new message (uses no native code)''' + if len(self.buf) >= 1 and self.buf[0] != 85: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 85: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + + 2 + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + diff --git a/pymavlink/dialects/v09/slugs.py b/pymavlink/dialects/v09/slugs.py new file mode 100644 index 0000000..2f98ee5 --- /dev/null +++ b/pymavlink/dialects/v09/slugs.py @@ -0,0 +1,5725 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: slugs.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "0.9" +DIALECT = "slugs" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 85, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if False: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at waypoint (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this waypoint an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this waypoint an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this waypoint for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this waypoint for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this waypoint for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this waypoint for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Empty''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system to + # control the vehicle attitude and the + # attitude of various sensors such + # as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Empty''' +enums['MAV_CMD'][176].param[3] = '''Empty''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera capturing. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera capturing.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system + # to control the vehicle attitude and the + # attitude of various + # devices such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + ''') +enums['MAV_CMD'][201].param[1] = '''Region of interest mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple cameras etc.)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Empty''' +enums['MAV_CMD'][241].param[6] = '''Empty''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[3] = '''Reserved''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_ENUM_END = 246 # +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next waypoint. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next waypoint.''') +MAV_ROI_WPINDEX = 2 # Point toward given waypoint. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given waypoint.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_CPU_LOAD = 170 +MAVLINK_MSG_ID_AIR_DATA = 171 +MAVLINK_MSG_ID_SENSOR_BIAS = 172 +MAVLINK_MSG_ID_DIAGNOSTIC = 173 +MAVLINK_MSG_ID_SLUGS_NAVIGATION = 176 +MAVLINK_MSG_ID_DATA_LOG = 177 +MAVLINK_MSG_ID_GPS_DATE_TIME = 179 +MAVLINK_MSG_ID_MID_LVL_CMDS = 180 +MAVLINK_MSG_ID_CTRL_SRFC_PT = 181 +MAVLINK_MSG_ID_SLUGS_ACTION = 183 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_BOOT = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 3 +MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_ACTION_ACK = 9 +MAVLINK_MSG_ID_ACTION = 10 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_SET_NAV_MODE = 12 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_GPS_STATUS = 27 +MAVLINK_MSG_ID_RAW_IMU = 28 +MAVLINK_MSG_ID_RAW_PRESSURE = 29 +MAVLINK_MSG_ID_SCALED_PRESSURE = 38 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_LOCAL_POSITION = 31 +MAVLINK_MSG_ID_GLOBAL_POSITION = 33 +MAVLINK_MSG_ID_GPS_RAW = 32 +MAVLINK_MSG_ID_SYS_STATUS = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37 +MAVLINK_MSG_ID_WAYPOINT = 39 +MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40 +MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41 +MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42 +MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43 +MAVLINK_MSG_ID_WAYPOINT_COUNT = 44 +MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45 +MAVLINK_MSG_ID_WAYPOINT_REACHED = 46 +MAVLINK_MSG_ID_WAYPOINT_ACK = 47 +MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51 +MAVLINK_MSG_ID_CONTROL_STATUS = 52 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_POSITION_TARGET = 63 +MAVLINK_MSG_ID_STATE_CORRECTION = 64 +MAVLINK_MSG_ID_SET_ALTITUDE = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_HIL_STATE = 67 +MAVLINK_MSG_ID_HIL_CONTROLS = 68 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND = 75 +MAVLINK_MSG_ID_COMMAND_ACK = 76 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140 +MAVLINK_MSG_ID_DEBUG_VECT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 253 +MAVLINK_MSG_ID_STATUSTEXT = 254 +MAVLINK_MSG_ID_DEBUG = 255 + +class MAVLink_cpu_load_message(MAVLink_message): + ''' + Sensor and DSC control loads. + ''' + id = MAVLINK_MSG_ID_CPU_LOAD + name = 'CPU_LOAD' + fieldnames = ['sensLoad', 'ctrlLoad', 'batVolt'] + ordered_fieldnames = [ 'sensLoad', 'ctrlLoad', 'batVolt' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 150 + + def __init__(self, sensLoad, ctrlLoad, batVolt): + MAVLink_message.__init__(self, MAVLink_cpu_load_message.id, MAVLink_cpu_load_message.name) + self._fieldnames = MAVLink_cpu_load_message.fieldnames + self.sensLoad = sensLoad + self.ctrlLoad = ctrlLoad + self.batVolt = batVolt + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 150, struct.pack('>BBH', self.sensLoad, self.ctrlLoad, self.batVolt)) + +class MAVLink_air_data_message(MAVLink_message): + ''' + Air data for altitude and airspeed computation. + ''' + id = MAVLINK_MSG_ID_AIR_DATA + name = 'AIR_DATA' + fieldnames = ['dynamicPressure', 'staticPressure', 'temperature'] + ordered_fieldnames = [ 'dynamicPressure', 'staticPressure', 'temperature' ] + format = '>ffH' + native_format = bytearray('>ffH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 232 + + def __init__(self, dynamicPressure, staticPressure, temperature): + MAVLink_message.__init__(self, MAVLink_air_data_message.id, MAVLink_air_data_message.name) + self._fieldnames = MAVLink_air_data_message.fieldnames + self.dynamicPressure = dynamicPressure + self.staticPressure = staticPressure + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 232, struct.pack('>ffH', self.dynamicPressure, self.staticPressure, self.temperature)) + +class MAVLink_sensor_bias_message(MAVLink_message): + ''' + Accelerometer and gyro biases. + ''' + id = MAVLINK_MSG_ID_SENSOR_BIAS + name = 'SENSOR_BIAS' + fieldnames = ['axBias', 'ayBias', 'azBias', 'gxBias', 'gyBias', 'gzBias'] + ordered_fieldnames = [ 'axBias', 'ayBias', 'azBias', 'gxBias', 'gyBias', 'gzBias' ] + format = '>ffffff' + native_format = bytearray('>ffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 168 + + def __init__(self, axBias, ayBias, azBias, gxBias, gyBias, gzBias): + MAVLink_message.__init__(self, MAVLink_sensor_bias_message.id, MAVLink_sensor_bias_message.name) + self._fieldnames = MAVLink_sensor_bias_message.fieldnames + self.axBias = axBias + self.ayBias = ayBias + self.azBias = azBias + self.gxBias = gxBias + self.gyBias = gyBias + self.gzBias = gzBias + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 168, struct.pack('>ffffff', self.axBias, self.ayBias, self.azBias, self.gxBias, self.gyBias, self.gzBias)) + +class MAVLink_diagnostic_message(MAVLink_message): + ''' + Configurable diagnostic messages. + ''' + id = MAVLINK_MSG_ID_DIAGNOSTIC + name = 'DIAGNOSTIC' + fieldnames = ['diagFl1', 'diagFl2', 'diagFl3', 'diagSh1', 'diagSh2', 'diagSh3'] + ordered_fieldnames = [ 'diagFl1', 'diagFl2', 'diagFl3', 'diagSh1', 'diagSh2', 'diagSh3' ] + format = '>fffhhh' + native_format = bytearray('>fffhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 2 + + def __init__(self, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3): + MAVLink_message.__init__(self, MAVLink_diagnostic_message.id, MAVLink_diagnostic_message.name) + self._fieldnames = MAVLink_diagnostic_message.fieldnames + self.diagFl1 = diagFl1 + self.diagFl2 = diagFl2 + self.diagFl3 = diagFl3 + self.diagSh1 = diagSh1 + self.diagSh2 = diagSh2 + self.diagSh3 = diagSh3 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 2, struct.pack('>fffhhh', self.diagFl1, self.diagFl2, self.diagFl3, self.diagSh1, self.diagSh2, self.diagSh3)) + +class MAVLink_slugs_navigation_message(MAVLink_message): + ''' + Data used in the navigation algorithm. + ''' + id = MAVLINK_MSG_ID_SLUGS_NAVIGATION + name = 'SLUGS_NAVIGATION' + fieldnames = ['u_m', 'phi_c', 'theta_c', 'psiDot_c', 'ay_body', 'totalDist', 'dist2Go', 'fromWP', 'toWP'] + ordered_fieldnames = [ 'u_m', 'phi_c', 'theta_c', 'psiDot_c', 'ay_body', 'totalDist', 'dist2Go', 'fromWP', 'toWP' ] + format = '>fffffffBB' + native_format = bytearray('>fffffffBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 120 + + def __init__(self, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP): + MAVLink_message.__init__(self, MAVLink_slugs_navigation_message.id, MAVLink_slugs_navigation_message.name) + self._fieldnames = MAVLink_slugs_navigation_message.fieldnames + self.u_m = u_m + self.phi_c = phi_c + self.theta_c = theta_c + self.psiDot_c = psiDot_c + self.ay_body = ay_body + self.totalDist = totalDist + self.dist2Go = dist2Go + self.fromWP = fromWP + self.toWP = toWP + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 120, struct.pack('>fffffffBB', self.u_m, self.phi_c, self.theta_c, self.psiDot_c, self.ay_body, self.totalDist, self.dist2Go, self.fromWP, self.toWP)) + +class MAVLink_data_log_message(MAVLink_message): + ''' + Configurable data log probes to be used inside Simulink + ''' + id = MAVLINK_MSG_ID_DATA_LOG + name = 'DATA_LOG' + fieldnames = ['fl_1', 'fl_2', 'fl_3', 'fl_4', 'fl_5', 'fl_6'] + ordered_fieldnames = [ 'fl_1', 'fl_2', 'fl_3', 'fl_4', 'fl_5', 'fl_6' ] + format = '>ffffff' + native_format = bytearray('>ffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 167 + + def __init__(self, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6): + MAVLink_message.__init__(self, MAVLink_data_log_message.id, MAVLink_data_log_message.name) + self._fieldnames = MAVLink_data_log_message.fieldnames + self.fl_1 = fl_1 + self.fl_2 = fl_2 + self.fl_3 = fl_3 + self.fl_4 = fl_4 + self.fl_5 = fl_5 + self.fl_6 = fl_6 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 167, struct.pack('>ffffff', self.fl_1, self.fl_2, self.fl_3, self.fl_4, self.fl_5, self.fl_6)) + +class MAVLink_gps_date_time_message(MAVLink_message): + ''' + Pilot console PWM messges. + ''' + id = MAVLINK_MSG_ID_GPS_DATE_TIME + name = 'GPS_DATE_TIME' + fieldnames = ['year', 'month', 'day', 'hour', 'min', 'sec', 'visSat'] + ordered_fieldnames = [ 'year', 'month', 'day', 'hour', 'min', 'sec', 'visSat' ] + format = '>BBBBBBB' + native_format = bytearray('>BBBBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 16 + + def __init__(self, year, month, day, hour, min, sec, visSat): + MAVLink_message.__init__(self, MAVLink_gps_date_time_message.id, MAVLink_gps_date_time_message.name) + self._fieldnames = MAVLink_gps_date_time_message.fieldnames + self.year = year + self.month = month + self.day = day + self.hour = hour + self.min = min + self.sec = sec + self.visSat = visSat + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 16, struct.pack('>BBBBBBB', self.year, self.month, self.day, self.hour, self.min, self.sec, self.visSat)) + +class MAVLink_mid_lvl_cmds_message(MAVLink_message): + ''' + Mid Level commands sent from the GS to the autopilot. These + are only sent when being opperated in mid-level commands mode + from the ground; for periodic report of these commands + generated from the autopilot see message XXXX. + ''' + id = MAVLINK_MSG_ID_MID_LVL_CMDS + name = 'MID_LVL_CMDS' + fieldnames = ['target', 'hCommand', 'uCommand', 'rCommand'] + ordered_fieldnames = [ 'target', 'hCommand', 'uCommand', 'rCommand' ] + format = '>Bfff' + native_format = bytearray('>Bfff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 2 + + def __init__(self, target, hCommand, uCommand, rCommand): + MAVLink_message.__init__(self, MAVLink_mid_lvl_cmds_message.id, MAVLink_mid_lvl_cmds_message.name) + self._fieldnames = MAVLink_mid_lvl_cmds_message.fieldnames + self.target = target + self.hCommand = hCommand + self.uCommand = uCommand + self.rCommand = rCommand + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 2, struct.pack('>Bfff', self.target, self.hCommand, self.uCommand, self.rCommand)) + +class MAVLink_ctrl_srfc_pt_message(MAVLink_message): + ''' + This message configures the Selective Passthrough mode. it + allows to select which control surfaces the Pilot can control + from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= 15-8 + Reserved 7 dt_pass 128 + 6 dla_pass 64 5 + dra_pass 32 4 dr_pass 16 + 3 dle_pass 8 2 + dre_pass 4 1 dlf_pass 2 + 0 drf_pass 1 Where Bit 15 is the + MSb. 0 = AP has control of the surface; 1 = Pilot Console has + control of the surface. + ''' + id = MAVLINK_MSG_ID_CTRL_SRFC_PT + name = 'CTRL_SRFC_PT' + fieldnames = ['target', 'bitfieldPt'] + ordered_fieldnames = [ 'target', 'bitfieldPt' ] + format = '>BH' + native_format = bytearray('>BH', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 52 + + def __init__(self, target, bitfieldPt): + MAVLink_message.__init__(self, MAVLink_ctrl_srfc_pt_message.id, MAVLink_ctrl_srfc_pt_message.name) + self._fieldnames = MAVLink_ctrl_srfc_pt_message.fieldnames + self.target = target + self.bitfieldPt = bitfieldPt + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 52, struct.pack('>BH', self.target, self.bitfieldPt)) + +class MAVLink_slugs_action_message(MAVLink_message): + ''' + Action messages focused on the SLUGS AP. + ''' + id = MAVLINK_MSG_ID_SLUGS_ACTION + name = 'SLUGS_ACTION' + fieldnames = ['target', 'actionId', 'actionVal'] + ordered_fieldnames = [ 'target', 'actionId', 'actionVal' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 202 + + def __init__(self, target, actionId, actionVal): + MAVLink_message.__init__(self, MAVLink_slugs_action_message.id, MAVLink_slugs_action_message.name) + self._fieldnames = MAVLink_slugs_action_message.fieldnames + self.target = target + self.actionId = actionId + self.actionVal = actionVal + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 202, struct.pack('>BBH', self.target, self.actionId, self.actionVal)) + +class MAVLink_heartbeat_message(MAVLink_message): + ''' + The heartbeat message shows that a system is present and + responding. The type of the MAV and Autopilot hardware allow + the receiving system to treat further messages from this + system appropriate (e.g. by laying out the user interface + based on the autopilot). + ''' + id = MAVLINK_MSG_ID_HEARTBEAT + name = 'HEARTBEAT' + fieldnames = ['type', 'autopilot', 'mavlink_version'] + ordered_fieldnames = [ 'type', 'autopilot', 'mavlink_version' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 72 + + def __init__(self, type, autopilot, mavlink_version): + MAVLink_message.__init__(self, MAVLink_heartbeat_message.id, MAVLink_heartbeat_message.name) + self._fieldnames = MAVLink_heartbeat_message.fieldnames + self.type = type + self.autopilot = autopilot + self.mavlink_version = mavlink_version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) + +class MAVLink_boot_message(MAVLink_message): + ''' + The boot message indicates that a system is starting. The + onboard software version allows to keep track of onboard + soft/firmware revisions. + ''' + id = MAVLINK_MSG_ID_BOOT + name = 'BOOT' + fieldnames = ['version'] + ordered_fieldnames = [ 'version' ] + format = '>I' + native_format = bytearray('>I', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 39 + + def __init__(self, version): + MAVLink_message.__init__(self, MAVLink_boot_message.id, MAVLink_boot_message.name) + self._fieldnames = MAVLink_boot_message.fieldnames + self.version = version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version)) + +class MAVLink_system_time_message(MAVLink_message): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME + name = 'SYSTEM_TIME' + fieldnames = ['time_usec'] + ordered_fieldnames = [ 'time_usec' ] + format = '>Q' + native_format = bytearray('>Q', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 190 + + def __init__(self, time_usec): + MAVLink_message.__init__(self, MAVLink_system_time_message.id, MAVLink_system_time_message.name) + self._fieldnames = MAVLink_system_time_message.fieldnames + self.time_usec = time_usec + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec)) + +class MAVLink_ping_message(MAVLink_message): + ''' + A ping message either requesting or responding to a ping. This + allows to measure the system latencies, including serial port, + radio modem and UDP connections. + ''' + id = MAVLINK_MSG_ID_PING + name = 'PING' + fieldnames = ['seq', 'target_system', 'target_component', 'time'] + ordered_fieldnames = [ 'seq', 'target_system', 'target_component', 'time' ] + format = '>IBBQ' + native_format = bytearray('>IBBQ', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 92 + + def __init__(self, seq, target_system, target_component, time): + MAVLink_message.__init__(self, MAVLink_ping_message.id, MAVLink_ping_message.name) + self._fieldnames = MAVLink_ping_message.fieldnames + self.seq = seq + self.target_system = target_system + self.target_component = target_component + self.time = time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time)) + +class MAVLink_system_time_utc_message(MAVLink_message): + ''' + UTC date and time from GPS module + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME_UTC + name = 'SYSTEM_TIME_UTC' + fieldnames = ['utc_date', 'utc_time'] + ordered_fieldnames = [ 'utc_date', 'utc_time' ] + format = '>II' + native_format = bytearray('>II', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 191 + + def __init__(self, utc_date, utc_time): + MAVLink_message.__init__(self, MAVLink_system_time_utc_message.id, MAVLink_system_time_utc_message.name) + self._fieldnames = MAVLink_system_time_utc_message.fieldnames + self.utc_date = utc_date + self.utc_time = utc_time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time)) + +class MAVLink_change_operator_control_message(MAVLink_message): + ''' + Request to control this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL + name = 'CHANGE_OPERATOR_CONTROL' + fieldnames = ['target_system', 'control_request', 'version', 'passkey'] + ordered_fieldnames = [ 'target_system', 'control_request', 'version', 'passkey' ] + format = '>BBB25s' + native_format = bytearray('>BBBc', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 25] + crc_extra = 217 + + def __init__(self, target_system, control_request, version, passkey): + MAVLink_message.__init__(self, MAVLink_change_operator_control_message.id, MAVLink_change_operator_control_message.name) + self._fieldnames = MAVLink_change_operator_control_message.fieldnames + self.target_system = target_system + self.control_request = control_request + self.version = version + self.passkey = passkey + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey)) + +class MAVLink_change_operator_control_ack_message(MAVLink_message): + ''' + Accept / deny control of this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK + name = 'CHANGE_OPERATOR_CONTROL_ACK' + fieldnames = ['gcs_system_id', 'control_request', 'ack'] + ordered_fieldnames = [ 'gcs_system_id', 'control_request', 'ack' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 104 + + def __init__(self, gcs_system_id, control_request, ack): + MAVLink_message.__init__(self, MAVLink_change_operator_control_ack_message.id, MAVLink_change_operator_control_ack_message.name) + self._fieldnames = MAVLink_change_operator_control_ack_message.fieldnames + self.gcs_system_id = gcs_system_id + self.control_request = control_request + self.ack = ack + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack)) + +class MAVLink_auth_key_message(MAVLink_message): + ''' + Emit an encrypted signature / key identifying this system. + PLEASE NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for true + safety. + ''' + id = MAVLINK_MSG_ID_AUTH_KEY + name = 'AUTH_KEY' + fieldnames = ['key'] + ordered_fieldnames = [ 'key' ] + format = '>32s' + native_format = bytearray('>c', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [32] + crc_extra = 119 + + def __init__(self, key): + MAVLink_message.__init__(self, MAVLink_auth_key_message.id, MAVLink_auth_key_message.name) + self._fieldnames = MAVLink_auth_key_message.fieldnames + self.key = key + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key)) + +class MAVLink_action_ack_message(MAVLink_message): + ''' + This message acknowledges an action. IMPORTANT: The + acknowledgement can be also negative, e.g. the MAV rejects a + reset message because it is in-flight. The action ids are + defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION_ACK + name = 'ACTION_ACK' + fieldnames = ['action', 'result'] + ordered_fieldnames = [ 'action', 'result' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 219 + + def __init__(self, action, result): + MAVLink_message.__init__(self, MAVLink_action_ack_message.id, MAVLink_action_ack_message.name) + self._fieldnames = MAVLink_action_ack_message.fieldnames + self.action = action + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result)) + +class MAVLink_action_message(MAVLink_message): + ''' + An action message allows to execute a certain onboard action. + These include liftoff, land, storing parameters too EEPROM, + shutddown, etc. The action ids are defined in ENUM MAV_ACTION + in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION + name = 'ACTION' + fieldnames = ['target', 'target_component', 'action'] + ordered_fieldnames = [ 'target', 'target_component', 'action' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 60 + + def __init__(self, target, target_component, action): + MAVLink_message.__init__(self, MAVLink_action_message.id, MAVLink_action_message.name) + self._fieldnames = MAVLink_action_message.fieldnames + self.target = target + self.target_component = target_component + self.action = action + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action)) + +class MAVLink_set_mode_message(MAVLink_message): + ''' + Set the system mode, as defined by enum MAV_MODE in + mavlink/include/mavlink_types.h. There is no target component + id as the mode is by definition for the overall aircraft, not + only for one component. + ''' + id = MAVLINK_MSG_ID_SET_MODE + name = 'SET_MODE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 186 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_mode_message.id, MAVLink_set_mode_message.name) + self._fieldnames = MAVLink_set_mode_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode)) + +class MAVLink_set_nav_mode_message(MAVLink_message): + ''' + Set the system navigation mode, as defined by enum + MAV_NAV_MODE in mavlink/include/mavlink_types.h. The + navigation mode applies to the whole aircraft and thus all + components. + ''' + id = MAVLINK_MSG_ID_SET_NAV_MODE + name = 'SET_NAV_MODE' + fieldnames = ['target', 'nav_mode'] + ordered_fieldnames = [ 'target', 'nav_mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 10 + + def __init__(self, target, nav_mode): + MAVLink_message.__init__(self, MAVLink_set_nav_mode_message.id, MAVLink_set_nav_mode_message.name) + self._fieldnames = MAVLink_set_nav_mode_message.fieldnames + self.target = target + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode)) + +class MAVLink_param_request_read_message(MAVLink_message): + ''' + Request to read the onboard parameter with the param_id string + id. Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_index' ] + format = '>BB15bh' + native_format = bytearray('>BBbh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 89 + + def __init__(self, target_system, target_component, param_id, param_index): + MAVLink_message.__init__(self, MAVLink_param_request_read_message.id, MAVLink_param_request_read_message.name) + self._fieldnames = MAVLink_param_request_read_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15bh', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_index)) + +class MAVLink_param_request_list_message(MAVLink_message): + ''' + Request all parameters of this component. After his request, + all parameters are emitted. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_LIST + name = 'PARAM_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 159 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_param_request_list_message.id, MAVLink_param_request_list_message.name) + self._fieldnames = MAVLink_param_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_param_value_message(MAVLink_message): + ''' + Emit the value of a onboard parameter. The inclusion of + param_count and param_index in the message allows the + recipient to keep track of received parameters and allows him + to re-request missing parameters after a loss or timeout. + ''' + id = MAVLINK_MSG_ID_PARAM_VALUE + name = 'PARAM_VALUE' + fieldnames = ['param_id', 'param_value', 'param_count', 'param_index'] + ordered_fieldnames = [ 'param_id', 'param_value', 'param_count', 'param_index' ] + format = '>15bfHH' + native_format = bytearray('>bfHH', 'ascii') + orders = [0, 1, 2, 3] + lengths = [15, 1, 1, 1] + array_lengths = [15, 0, 0, 0] + crc_extra = 162 + + def __init__(self, param_id, param_value, param_count, param_index): + MAVLink_message.__init__(self, MAVLink_param_value_message.id, MAVLink_param_value_message.name) + self._fieldnames = MAVLink_param_value_message.fieldnames + self.param_id = param_id + self.param_value = param_value + self.param_count = param_count + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>15bfHH', self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value, self.param_count, self.param_index)) + +class MAVLink_param_set_message(MAVLink_message): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to + default on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents + to EEPROM. IMPORTANT: The receiving component should + acknowledge the new parameter value by sending a param_value + message to all communication partners. This will also ensure + that multiple GCS all have an up-to-date list of all + parameters. If the sending GCS did not receive a PARAM_VALUE + message within its timeout time, it should re-send the + PARAM_SET message. + ''' + id = MAVLINK_MSG_ID_PARAM_SET + name = 'PARAM_SET' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_value'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_value' ] + format = '>BB15bf' + native_format = bytearray('>BBbf', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 121 + + def __init__(self, target_system, target_component, param_id, param_value): + MAVLink_message.__init__(self, MAVLink_param_set_message.id, MAVLink_param_set_message.name) + self._fieldnames = MAVLink_param_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_value = param_value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15bf', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value)) + +class MAVLink_gps_raw_int_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW_INT + name = 'GPS_RAW_INT' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBiiiffff' + native_format = bytearray('>QBiiiffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 149 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_int_message.id, MAVLink_gps_raw_int_message.name) + self._fieldnames = MAVLink_gps_raw_int_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_scaled_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should contain the scaled values to the described + units + ''' + id = MAVLINK_MSG_ID_SCALED_IMU + name = 'SCALED_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 222 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_scaled_imu_message.id, MAVLink_scaled_imu_message.name) + self._fieldnames = MAVLink_scaled_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_gps_status_message(MAVLink_message): + ''' + The positioning status, as reported by GPS. This message is + intended to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION for the + global position estimate. This message can contain information + for up to 20 satellites. + ''' + id = MAVLINK_MSG_ID_GPS_STATUS + name = 'GPS_STATUS' + fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr'] + ordered_fieldnames = [ 'satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr' ] + format = '>B20b20b20b20b20b' + native_format = bytearray('>Bbbbbb', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 20, 20, 20, 20, 20] + array_lengths = [0, 20, 20, 20, 20, 20] + crc_extra = 110 + + def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + MAVLink_message.__init__(self, MAVLink_gps_status_message.id, MAVLink_gps_status_message.name) + self._fieldnames = MAVLink_gps_status_message.fieldnames + self.satellites_visible = satellites_visible + self.satellite_prn = satellite_prn + self.satellite_used = satellite_used + self.satellite_elevation = satellite_elevation + self.satellite_azimuth = satellite_azimuth + self.satellite_snr = satellite_snr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 110, struct.pack('>B20b20b20b20b20b', self.satellites_visible, self.satellite_prn[0], self.satellite_prn[1], self.satellite_prn[2], self.satellite_prn[3], self.satellite_prn[4], self.satellite_prn[5], self.satellite_prn[6], self.satellite_prn[7], self.satellite_prn[8], self.satellite_prn[9], self.satellite_prn[10], self.satellite_prn[11], self.satellite_prn[12], self.satellite_prn[13], self.satellite_prn[14], self.satellite_prn[15], self.satellite_prn[16], self.satellite_prn[17], self.satellite_prn[18], self.satellite_prn[19], self.satellite_used[0], self.satellite_used[1], self.satellite_used[2], self.satellite_used[3], self.satellite_used[4], self.satellite_used[5], self.satellite_used[6], self.satellite_used[7], self.satellite_used[8], self.satellite_used[9], self.satellite_used[10], self.satellite_used[11], self.satellite_used[12], self.satellite_used[13], self.satellite_used[14], self.satellite_used[15], self.satellite_used[16], self.satellite_used[17], self.satellite_used[18], self.satellite_used[19], self.satellite_elevation[0], self.satellite_elevation[1], self.satellite_elevation[2], self.satellite_elevation[3], self.satellite_elevation[4], self.satellite_elevation[5], self.satellite_elevation[6], self.satellite_elevation[7], self.satellite_elevation[8], self.satellite_elevation[9], self.satellite_elevation[10], self.satellite_elevation[11], self.satellite_elevation[12], self.satellite_elevation[13], self.satellite_elevation[14], self.satellite_elevation[15], self.satellite_elevation[16], self.satellite_elevation[17], self.satellite_elevation[18], self.satellite_elevation[19], self.satellite_azimuth[0], self.satellite_azimuth[1], self.satellite_azimuth[2], self.satellite_azimuth[3], self.satellite_azimuth[4], self.satellite_azimuth[5], self.satellite_azimuth[6], self.satellite_azimuth[7], self.satellite_azimuth[8], self.satellite_azimuth[9], self.satellite_azimuth[10], self.satellite_azimuth[11], self.satellite_azimuth[12], self.satellite_azimuth[13], self.satellite_azimuth[14], self.satellite_azimuth[15], self.satellite_azimuth[16], self.satellite_azimuth[17], self.satellite_azimuth[18], self.satellite_azimuth[19], self.satellite_snr[0], self.satellite_snr[1], self.satellite_snr[2], self.satellite_snr[3], self.satellite_snr[4], self.satellite_snr[5], self.satellite_snr[6], self.satellite_snr[7], self.satellite_snr[8], self.satellite_snr[9], self.satellite_snr[10], self.satellite_snr[11], self.satellite_snr[12], self.satellite_snr[13], self.satellite_snr[14], self.satellite_snr[15], self.satellite_snr[16], self.satellite_snr[17], self.satellite_snr[18], self.satellite_snr[19])) + +class MAVLink_raw_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should always contain the true raw values without any + scaling to allow data capture and system debugging. + ''' + id = MAVLINK_MSG_ID_RAW_IMU + name = 'RAW_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 179 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_raw_imu_message.id, MAVLink_raw_imu_message.name) + self._fieldnames = MAVLink_raw_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_raw_pressure_message(MAVLink_message): + ''' + The RAW pressure readings for the typical setup of one + absolute pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + ''' + id = MAVLINK_MSG_ID_RAW_PRESSURE + name = 'RAW_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature' ] + format = '>Qhhhh' + native_format = bytearray('>Qhhhh', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 136 + + def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature): + MAVLink_message.__init__(self, MAVLink_raw_pressure_message.id, MAVLink_raw_pressure_message.name) + self._fieldnames = MAVLink_raw_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff1 = press_diff1 + self.press_diff2 = press_diff2 + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature)) + +class MAVLink_scaled_pressure_message(MAVLink_message): + ''' + The pressure readings for the typical setup of one absolute + and differential pressure sensor. The units are as specified + in each field. + ''' + id = MAVLINK_MSG_ID_SCALED_PRESSURE + name = 'SCALED_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff', 'temperature' ] + format = '>Qffh' + native_format = bytearray('>Qffh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 229 + + def __init__(self, usec, press_abs, press_diff, temperature): + MAVLink_message.__init__(self, MAVLink_scaled_pressure_message.id, MAVLink_scaled_pressure_message.name) + self._fieldnames = MAVLink_scaled_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff = press_diff + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature)) + +class MAVLink_attitude_message(MAVLink_message): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, + X-front, Y-right). + ''' + id = MAVLINK_MSG_ID_ATTITUDE + name = 'ATTITUDE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 66 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + MAVLink_message.__init__(self, MAVLink_attitude_message.id, MAVLink_attitude_message.name) + self._fieldnames = MAVLink_attitude_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed)) + +class MAVLink_local_position_message(MAVLink_message): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, Z-axis down + (aeronautical frame) + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION + name = 'LOCAL_POSITION' + fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'x', 'y', 'z', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, usec, x, y, z, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_local_position_message.id, MAVLink_local_position_message.name) + self._fieldnames = MAVLink_local_position_message.fieldnames + self.usec = usec + self.x = x + self.y = y + self.z = z + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz)) + +class MAVLink_global_position_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). Coordinate frame is right-handed, Z-axis up + (GPS frame) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION + name = 'GLOBAL_POSITION' + fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 147 + + def __init__(self, usec, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_message.id, MAVLink_global_position_message.name) + self._fieldnames = MAVLink_global_position_message.fieldnames + self.usec = usec + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_gps_raw_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW + name = 'GPS_RAW' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBfffffff' + native_format = bytearray('>QBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 185 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_message.id, MAVLink_gps_raw_message.name) + self._fieldnames = MAVLink_gps_raw_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_sys_status_message(MAVLink_message): + ''' + The general system state. If the system is following the + MAVLink standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is either + LOCKED (motors shut down and locked), MANUAL (system under RC + control), GUIDED (system with autonomous position control, + position setpoint controlled manually) or AUTO (system guided + by path/waypoint planner). The NAV_MODE defined the current + flight state: LIFTOFF (often an open-loop maneuver), LANDING, + WAYPOINTS or VECTOR. This represents the internal navigation + state machine. The system status shows wether the system is + currently active or not and if an emergency occured. During + the CRITICAL and EMERGENCY states the MAV is still considered + to be active, but should start emergency procedures + autonomously. After a failure occured it should first move + from active to critical to allow manual intervention and then + move to emergency after a certain timeout. + ''' + id = MAVLINK_MSG_ID_SYS_STATUS + name = 'SYS_STATUS' + fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop'] + ordered_fieldnames = [ 'mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop' ] + format = '>BBBHHHH' + native_format = bytearray('>BBBHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 112 + + def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + MAVLink_message.__init__(self, MAVLink_sys_status_message.id, MAVLink_sys_status_message.name) + self._fieldnames = MAVLink_sys_status_message.fieldnames + self.mode = mode + self.nav_mode = nav_mode + self.status = status + self.load = load + self.vbat = vbat + self.battery_remaining = battery_remaining + self.packet_drop = packet_drop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop)) + +class MAVLink_rc_channels_raw_message(MAVLink_message): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_RAW + name = 'RC_CHANNELS_RAW' + fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi'] + ordered_fieldnames = [ 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi' ] + format = '>HHHHHHHHB' + native_format = bytearray('>HHHHHHHHB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 252 + + def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_raw_message.id, MAVLink_rc_channels_raw_message.name) + self._fieldnames = MAVLink_rc_channels_raw_message.fieldnames + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi)) + +class MAVLink_rc_channels_scaled_message(MAVLink_message): + ''' + The scaled values of the RC channels received. (-100%) -10000, + (0%) 0, (100%) 10000 + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_SCALED + name = 'RC_CHANNELS_SCALED' + fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi'] + ordered_fieldnames = [ 'chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi' ] + format = '>hhhhhhhhB' + native_format = bytearray('>hhhhhhhhB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 162 + + def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_scaled_message.id, MAVLink_rc_channels_scaled_message.name) + self._fieldnames = MAVLink_rc_channels_scaled_message.fieldnames + self.chan1_scaled = chan1_scaled + self.chan2_scaled = chan2_scaled + self.chan3_scaled = chan3_scaled + self.chan4_scaled = chan4_scaled + self.chan5_scaled = chan5_scaled + self.chan6_scaled = chan6_scaled + self.chan7_scaled = chan7_scaled + self.chan8_scaled = chan8_scaled + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi)) + +class MAVLink_servo_output_raw_message(MAVLink_message): + ''' + The RAW values of the servo outputs (for RC input from the + remote, use the RC_CHANNELS messages). The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + ''' + id = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW + name = 'SERVO_OUTPUT_RAW' + fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw'] + ordered_fieldnames = [ 'servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw' ] + format = '>HHHHHHHH' + native_format = bytearray('>HHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + MAVLink_message.__init__(self, MAVLink_servo_output_raw_message.id, MAVLink_servo_output_raw_message.name) + self._fieldnames = MAVLink_servo_output_raw_message.fieldnames + self.servo1_raw = servo1_raw + self.servo2_raw = servo2_raw + self.servo3_raw = servo3_raw + self.servo4_raw = servo4_raw + self.servo5_raw = servo5_raw + self.servo6_raw = servo6_raw + self.servo7_raw = servo7_raw + self.servo8_raw = servo8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw)) + +class MAVLink_waypoint_message(MAVLink_message): + ''' + Message encoding a waypoint. This message is emitted to + announce the presence of a waypoint and to set a waypoint + on the system. The waypoint can be either in x, y, z meters + (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is + Z-down, right handed, global frame is Z-up, right handed + ''' + id = MAVLINK_MSG_ID_WAYPOINT + name = 'WAYPOINT' + fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z' ] + format = '>BBHBBBBfffffff' + native_format = bytearray('>BBHBBBBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 128 + + def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + MAVLink_message.__init__(self, MAVLink_waypoint_message.id, MAVLink_waypoint_message.name) + self._fieldnames = MAVLink_waypoint_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + self.frame = frame + self.command = command + self.current = current + self.autocontinue = autocontinue + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z)) + +class MAVLink_waypoint_request_message(MAVLink_message): + ''' + Request the information of the waypoint with the sequence + number seq. The response of the system to this message should + be a WAYPOINT message. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST + name = 'WAYPOINT_REQUEST' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 9 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_request_message.id, MAVLink_waypoint_request_message.name) + self._fieldnames = MAVLink_waypoint_request_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_set_current_message(MAVLink_message): + ''' + Set the waypoint with sequence number seq as current waypoint. + This means that the MAV will continue to this waypoint on the + shortest path (not following the waypoints in-between). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT + name = 'WAYPOINT_SET_CURRENT' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 106 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_set_current_message.id, MAVLink_waypoint_set_current_message.name) + self._fieldnames = MAVLink_waypoint_set_current_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_current_message(MAVLink_message): + ''' + Message that announces the sequence number of the current + active waypoint. The MAV will fly towards this waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CURRENT + name = 'WAYPOINT_CURRENT' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 101 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_current_message.id, MAVLink_waypoint_current_message.name) + self._fieldnames = MAVLink_waypoint_current_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_request_list_message(MAVLink_message): + ''' + Request the overall list of waypoints from the + system/component. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST + name = 'WAYPOINT_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_request_list_message.id, MAVLink_waypoint_request_list_message.name) + self._fieldnames = MAVLink_waypoint_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_count_message(MAVLink_message): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST + by the MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of waypoints. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_COUNT + name = 'WAYPOINT_COUNT' + fieldnames = ['target_system', 'target_component', 'count'] + ordered_fieldnames = [ 'target_system', 'target_component', 'count' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 4 + + def __init__(self, target_system, target_component, count): + MAVLink_message.__init__(self, MAVLink_waypoint_count_message.id, MAVLink_waypoint_count_message.name) + self._fieldnames = MAVLink_waypoint_count_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.count = count + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count)) + +class MAVLink_waypoint_clear_all_message(MAVLink_message): + ''' + Delete all waypoints at once. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL + name = 'WAYPOINT_CLEAR_ALL' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 229 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_clear_all_message.id, MAVLink_waypoint_clear_all_message.name) + self._fieldnames = MAVLink_waypoint_clear_all_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_reached_message(MAVLink_message): + ''' + A certain waypoint has been reached. The system will either + hold this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REACHED + name = 'WAYPOINT_REACHED' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 21 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_reached_message.id, MAVLink_waypoint_reached_message.name) + self._fieldnames = MAVLink_waypoint_reached_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_ack_message(MAVLink_message): + ''' + Ack message during waypoint handling. The type field states if + this message is a positive ack (type=0) or if an error + happened (type=non-zero). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_ACK + name = 'WAYPOINT_ACK' + fieldnames = ['target_system', 'target_component', 'type'] + ordered_fieldnames = [ 'target_system', 'target_component', 'type' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 214 + + def __init__(self, target_system, target_component, type): + MAVLink_message.__init__(self, MAVLink_waypoint_ack_message.id, MAVLink_waypoint_ack_message.name) + self._fieldnames = MAVLink_waypoint_ack_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.type = type + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type)) + +class MAVLink_gps_set_global_origin_message(MAVLink_message): + ''' + As local waypoints exist, the global waypoint reference allows + to transform between the local coordinate frame and the global + (GPS) coordinate frame. This can be necessary when e.g. in- + and outdoor settings are connected and the MAV should move + from in- to outdoor. + ''' + id = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN + name = 'GPS_SET_GLOBAL_ORIGIN' + fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'target_system', 'target_component', 'latitude', 'longitude', 'altitude' ] + format = '>BBiii' + native_format = bytearray('>BBiii', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, target_system, target_component, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_set_global_origin_message.id, MAVLink_gps_set_global_origin_message.name) + self._fieldnames = MAVLink_gps_set_global_origin_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude)) + +class MAVLink_gps_local_origin_set_message(MAVLink_message): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + ''' + id = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET + name = 'GPS_LOCAL_ORIGIN_SET' + fieldnames = ['latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'latitude', 'longitude', 'altitude' ] + format = '>iii' + native_format = bytearray('>iii', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 14 + + def __init__(self, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_local_origin_set_message.id, MAVLink_gps_local_origin_set_message.name) + self._fieldnames = MAVLink_gps_local_origin_set_message.fieldnames + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude)) + +class MAVLink_local_position_setpoint_set_message(MAVLink_message): + ''' + Set the setpoint for a local position controller. This is the + position in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the onboard + position controller. As some MAVs have a degree of freedom in + yaw (e.g. all helicopters/quadrotors), the desired yaw angle + is part of the message. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET + name = 'LOCAL_POSITION_SETPOINT_SET' + fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'x', 'y', 'z', 'yaw' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 206 + + def __init__(self, target_system, target_component, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_set_message.id, MAVLink_local_position_setpoint_set_message.name) + self._fieldnames = MAVLink_local_position_setpoint_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw)) + +class MAVLink_local_position_setpoint_message(MAVLink_message): + ''' + Transmit the current local setpoint of the controller to other + MAVs (collision avoidance) and to the GCS. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT + name = 'LOCAL_POSITION_SETPOINT' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 50 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_message.id, MAVLink_local_position_setpoint_message.name) + self._fieldnames = MAVLink_local_position_setpoint_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_control_status_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_CONTROL_STATUS + name = 'CONTROL_STATUS' + fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw'] + ordered_fieldnames = [ 'position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw' ] + format = '>BBBBBBBB' + native_format = bytearray('>BBBBBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 157 + + def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + MAVLink_message.__init__(self, MAVLink_control_status_message.id, MAVLink_control_status_message.name) + self._fieldnames = MAVLink_control_status_message.fieldnames + self.position_fix = position_fix + self.vision_fix = vision_fix + self.gps_fix = gps_fix + self.ahrs_health = ahrs_health + self.control_att = control_att + self.control_pos_xy = control_pos_xy + self.control_pos_z = control_pos_z + self.control_pos_yaw = control_pos_yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw)) + +class MAVLink_safety_set_allowed_area_message(MAVLink_message): + ''' + Set a safety zone (volume), which is defined by two corners of + a cube. This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. Safety + areas are often enforced by national or competition + regulations. + ''' + id = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA + name = 'SAFETY_SET_ALLOWED_AREA' + fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>BBBffffff' + native_format = bytearray('>BBBffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_set_allowed_area_message.id, MAVLink_safety_set_allowed_area_message.name) + self._fieldnames = MAVLink_safety_set_allowed_area_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_safety_allowed_area_message(MAVLink_message): + ''' + Read out the safety zone the MAV currently assumes. + ''' + id = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA + name = 'SAFETY_ALLOWED_AREA' + fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>Bffffff' + native_format = bytearray('>Bffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 108 + + def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_allowed_area_message.id, MAVLink_safety_allowed_area_message.name) + self._fieldnames = MAVLink_safety_allowed_area_message.fieldnames + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST + name = 'SET_ROLL_PITCH_YAW_THRUST' + fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_thrust_message.id, MAVLink_set_roll_pitch_yaw_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST + name = 'SET_ROLL_PITCH_YAW_SPEED_THRUST' + fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 95 + + def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_speed_thrust_message.id, MAVLink_set_roll_pitch_yaw_speed_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_speed_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 5 + + def __init__(self, time_us, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active + on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 127 + + def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_nav_controller_output_message(MAVLink_message): + ''' + Outputs of the APM navigation controller. The primary use of + this message is to check the response and signs of the + controller before actual flight and to assist with tuning + controller parameters + ''' + id = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT + name = 'NAV_CONTROLLER_OUTPUT' + fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error'] + ordered_fieldnames = [ 'nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error' ] + format = '>ffhhHfff' + native_format = bytearray('>ffhhHfff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 57 + + def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + MAVLink_message.__init__(self, MAVLink_nav_controller_output_message.id, MAVLink_nav_controller_output_message.name) + self._fieldnames = MAVLink_nav_controller_output_message.fieldnames + self.nav_roll = nav_roll + self.nav_pitch = nav_pitch + self.nav_bearing = nav_bearing + self.target_bearing = target_bearing + self.wp_dist = wp_dist + self.alt_error = alt_error + self.aspd_error = aspd_error + self.xtrack_error = xtrack_error + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error)) + +class MAVLink_position_target_message(MAVLink_message): + ''' + The goal position of the system. This position is the input to + any navigation or path planning algorithm and does NOT + represent the current controller setpoint. + ''' + id = MAVLINK_MSG_ID_POSITION_TARGET + name = 'POSITION_TARGET' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_position_target_message.id, MAVLink_position_target_message.name) + self._fieldnames = MAVLink_position_target_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_state_correction_message(MAVLink_message): + ''' + Corrects the systems state by adding an error correction term + to the position and velocity, and by rotating the attitude by + a correction angle. + ''' + id = MAVLINK_MSG_ID_STATE_CORRECTION + name = 'STATE_CORRECTION' + fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr'] + ordered_fieldnames = [ 'xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr' ] + format = '>fffffffff' + native_format = bytearray('>fffffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 130 + + def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + MAVLink_message.__init__(self, MAVLink_state_correction_message.id, MAVLink_state_correction_message.name) + self._fieldnames = MAVLink_state_correction_message.fieldnames + self.xErr = xErr + self.yErr = yErr + self.zErr = zErr + self.rollErr = rollErr + self.pitchErr = pitchErr + self.yawErr = yawErr + self.vxErr = vxErr + self.vyErr = vyErr + self.vzErr = vzErr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr)) + +class MAVLink_set_altitude_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_SET_ALTITUDE + name = 'SET_ALTITUDE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BI' + native_format = bytearray('>BI', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 119 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_altitude_message.id, MAVLink_set_altitude_message.name) + self._fieldnames = MAVLink_set_altitude_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode)) + +class MAVLink_request_data_stream_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_REQUEST_DATA_STREAM + name = 'REQUEST_DATA_STREAM' + fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop'] + ordered_fieldnames = [ 'target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop' ] + format = '>BBBHB' + native_format = bytearray('>BBBHB', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 193 + + def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + MAVLink_message.__init__(self, MAVLink_request_data_stream_message.id, MAVLink_request_data_stream_message.name) + self._fieldnames = MAVLink_request_data_stream_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.req_stream_id = req_stream_id + self.req_message_rate = req_message_rate + self.start_stop = start_stop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop)) + +class MAVLink_hil_state_message(MAVLink_message): + ''' + This packet is useful for high throughput + applications such as hardware in the loop simulations. + ''' + id = MAVLINK_MSG_ID_HIL_STATE + name = 'HIL_STATE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc' ] + format = '>Qffffffiiihhhhhh' + native_format = bytearray('>Qffffffiiihhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 191 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + MAVLink_message.__init__(self, MAVLink_hil_state_message.id, MAVLink_hil_state_message.name) + self._fieldnames = MAVLink_hil_state_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc)) + +class MAVLink_hil_controls_message(MAVLink_message): + ''' + Hardware in the loop control outputs + ''' + id = MAVLINK_MSG_ID_HIL_CONTROLS + name = 'HIL_CONTROLS' + fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode'] + ordered_fieldnames = [ 'time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode' ] + format = '>QffffBB' + native_format = bytearray('>QffffBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 236 + + def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + MAVLink_message.__init__(self, MAVLink_hil_controls_message.id, MAVLink_hil_controls_message.name) + self._fieldnames = MAVLink_hil_controls_message.fieldnames + self.time_us = time_us + self.roll_ailerons = roll_ailerons + self.pitch_elevator = pitch_elevator + self.yaw_rudder = yaw_rudder + self.throttle = throttle + self.mode = mode + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode)) + +class MAVLink_manual_control_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_MANUAL_CONTROL + name = 'MANUAL_CONTROL' + fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual'] + ordered_fieldnames = [ 'target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual' ] + format = '>BffffBBBB' + native_format = bytearray('>BffffBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 158 + + def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + MAVLink_message.__init__(self, MAVLink_manual_control_message.id, MAVLink_manual_control_message.name) + self._fieldnames = MAVLink_manual_control_message.fieldnames + self.target = target + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + self.roll_manual = roll_manual + self.pitch_manual = pitch_manual + self.yaw_manual = yaw_manual + self.thrust_manual = thrust_manual + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual)) + +class MAVLink_rc_channels_override_message(MAVLink_message): + ''' + The RAW values of the RC channels sent to the MAV to override + info received from the RC radio. A value of -1 means no change + to that channel. A value of 0 means control of that channel + should be released back to the RC radio. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE + name = 'RC_CHANNELS_OVERRIDE' + fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw' ] + format = '>BBHHHHHHHH' + native_format = bytearray('>BBHHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 143 + + def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + MAVLink_message.__init__(self, MAVLink_rc_channels_override_message.id, MAVLink_rc_channels_override_message.name) + self._fieldnames = MAVLink_rc_channels_override_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw)) + +class MAVLink_global_position_int_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). The position is in GPS-frame (right-handed, + Z-up) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION_INT + name = 'GLOBAL_POSITION_INT' + fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>iiihhh' + native_format = bytearray('>iiihhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 104 + + def __init__(self, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_int_message.id, MAVLink_global_position_int_message.name) + self._fieldnames = MAVLink_global_position_int_message.fieldnames + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_vfr_hud_message(MAVLink_message): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + ''' + id = MAVLINK_MSG_ID_VFR_HUD + name = 'VFR_HUD' + fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb'] + ordered_fieldnames = [ 'airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb' ] + format = '>ffhHff' + native_format = bytearray('>ffhHff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 123 + + def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb): + MAVLink_message.__init__(self, MAVLink_vfr_hud_message.id, MAVLink_vfr_hud_message.name) + self._fieldnames = MAVLink_vfr_hud_message.fieldnames + self.airspeed = airspeed + self.groundspeed = groundspeed + self.heading = heading + self.throttle = throttle + self.alt = alt + self.climb = climb + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb)) + +class MAVLink_command_message(MAVLink_message): + ''' + Send a command with up to four parameters to the MAV + ''' + id = MAVLINK_MSG_ID_COMMAND + name = 'COMMAND' + fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4'] + ordered_fieldnames = [ 'target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4' ] + format = '>BBBBffff' + native_format = bytearray('>BBBBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 131 + + def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + MAVLink_message.__init__(self, MAVLink_command_message.id, MAVLink_command_message.name) + self._fieldnames = MAVLink_command_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.command = command + self.confirmation = confirmation + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4)) + +class MAVLink_command_ack_message(MAVLink_message): + ''' + Report status of a command. Includes feedback wether the + command was executed + ''' + id = MAVLINK_MSG_ID_COMMAND_ACK + name = 'COMMAND_ACK' + fieldnames = ['command', 'result'] + ordered_fieldnames = [ 'command', 'result' ] + format = '>ff' + native_format = bytearray('>ff', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 8 + + def __init__(self, command, result): + MAVLink_message.__init__(self, MAVLink_command_ack_message.id, MAVLink_command_ack_message.name) + self._fieldnames = MAVLink_command_ack_message.fieldnames + self.command = command + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result)) + +class MAVLink_optical_flow_message(MAVLink_message): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + ''' + id = MAVLINK_MSG_ID_OPTICAL_FLOW + name = 'OPTICAL_FLOW' + fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance'] + ordered_fieldnames = [ 'time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance' ] + format = '>QBhhBf' + native_format = bytearray('>QBhhBf', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 174 + + def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + MAVLink_message.__init__(self, MAVLink_optical_flow_message.id, MAVLink_optical_flow_message.name) + self._fieldnames = MAVLink_optical_flow_message.fieldnames + self.time = time + self.sensor_id = sensor_id + self.flow_x = flow_x + self.flow_y = flow_y + self.quality = quality + self.ground_distance = ground_distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance)) + +class MAVLink_object_detection_event_message(MAVLink_message): + ''' + Object has been detected + ''' + id = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT + name = 'OBJECT_DETECTION_EVENT' + fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance'] + ordered_fieldnames = [ 'time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance' ] + format = '>IHB20sBff' + native_format = bytearray('>IHBcBff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 20, 0, 0, 0] + crc_extra = 155 + + def __init__(self, time, object_id, type, name, quality, bearing, distance): + MAVLink_message.__init__(self, MAVLink_object_detection_event_message.id, MAVLink_object_detection_event_message.name) + self._fieldnames = MAVLink_object_detection_event_message.fieldnames + self.time = time + self.object_id = object_id + self.type = type + self.name = name + self.quality = quality + self.bearing = bearing + self.distance = distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance)) + +class MAVLink_debug_vect_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_DEBUG_VECT + name = 'DEBUG_VECT' + fieldnames = ['name', 'usec', 'x', 'y', 'z'] + ordered_fieldnames = [ 'name', 'usec', 'x', 'y', 'z' ] + format = '>10sQfff' + native_format = bytearray('>cQfff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [10, 0, 0, 0, 0] + crc_extra = 178 + + def __init__(self, name, usec, x, y, z): + MAVLink_message.__init__(self, MAVLink_debug_vect_message.id, MAVLink_debug_vect_message.name) + self._fieldnames = MAVLink_debug_vect_message.fieldnames + self.name = name + self.usec = usec + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z)) + +class MAVLink_named_value_float_message(MAVLink_message): + ''' + Send a key-value pair as float. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT + name = 'NAMED_VALUE_FLOAT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10sf' + native_format = bytearray('>cf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 224 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_float_message.id, MAVLink_named_value_float_message.name) + self._fieldnames = MAVLink_named_value_float_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value)) + +class MAVLink_named_value_int_message(MAVLink_message): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_INT + name = 'NAMED_VALUE_INT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10si' + native_format = bytearray('>ci', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 60 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_int_message.id, MAVLink_named_value_int_message.name) + self._fieldnames = MAVLink_named_value_int_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value)) + +class MAVLink_statustext_message(MAVLink_message): + ''' + Status text message. These messages are printed in yellow in + the COMM console of QGroundControl. WARNING: They consume + quite some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages are + buffered on the MCU and sent only at a limited rate (e.g. 10 + Hz). + ''' + id = MAVLINK_MSG_ID_STATUSTEXT + name = 'STATUSTEXT' + fieldnames = ['severity', 'text'] + ordered_fieldnames = [ 'severity', 'text' ] + format = '>B50b' + native_format = bytearray('>Bb', 'ascii') + orders = [0, 1] + lengths = [1, 50] + array_lengths = [0, 50] + crc_extra = 106 + + def __init__(self, severity, text): + MAVLink_message.__init__(self, MAVLink_statustext_message.id, MAVLink_statustext_message.name) + self._fieldnames = MAVLink_statustext_message.fieldnames + self.severity = severity + self.text = text + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>B50b', self.severity, self.text[0], self.text[1], self.text[2], self.text[3], self.text[4], self.text[5], self.text[6], self.text[7], self.text[8], self.text[9], self.text[10], self.text[11], self.text[12], self.text[13], self.text[14], self.text[15], self.text[16], self.text[17], self.text[18], self.text[19], self.text[20], self.text[21], self.text[22], self.text[23], self.text[24], self.text[25], self.text[26], self.text[27], self.text[28], self.text[29], self.text[30], self.text[31], self.text[32], self.text[33], self.text[34], self.text[35], self.text[36], self.text[37], self.text[38], self.text[39], self.text[40], self.text[41], self.text[42], self.text[43], self.text[44], self.text[45], self.text[46], self.text[47], self.text[48], self.text[49])) + +class MAVLink_debug_message(MAVLink_message): + ''' + Send a debug value. The index is used to discriminate between + values. These values show up in the plot of QGroundControl as + DEBUG N. + ''' + id = MAVLINK_MSG_ID_DEBUG + name = 'DEBUG' + fieldnames = ['ind', 'value'] + ordered_fieldnames = [ 'ind', 'value' ] + format = '>Bf' + native_format = bytearray('>Bf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 7 + + def __init__(self, ind, value): + MAVLink_message.__init__(self, MAVLink_debug_message.id, MAVLink_debug_message.name) + self._fieldnames = MAVLink_debug_message.fieldnames + self.ind = ind + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value)) + + +mavlink_map = { + MAVLINK_MSG_ID_CPU_LOAD : MAVLink_cpu_load_message, + MAVLINK_MSG_ID_AIR_DATA : MAVLink_air_data_message, + MAVLINK_MSG_ID_SENSOR_BIAS : MAVLink_sensor_bias_message, + MAVLINK_MSG_ID_DIAGNOSTIC : MAVLink_diagnostic_message, + MAVLINK_MSG_ID_SLUGS_NAVIGATION : MAVLink_slugs_navigation_message, + MAVLINK_MSG_ID_DATA_LOG : MAVLink_data_log_message, + MAVLINK_MSG_ID_GPS_DATE_TIME : MAVLink_gps_date_time_message, + MAVLINK_MSG_ID_MID_LVL_CMDS : MAVLink_mid_lvl_cmds_message, + MAVLINK_MSG_ID_CTRL_SRFC_PT : MAVLink_ctrl_srfc_pt_message, + MAVLINK_MSG_ID_SLUGS_ACTION : MAVLink_slugs_action_message, + MAVLINK_MSG_ID_HEARTBEAT : MAVLink_heartbeat_message, + MAVLINK_MSG_ID_BOOT : MAVLink_boot_message, + MAVLINK_MSG_ID_SYSTEM_TIME : MAVLink_system_time_message, + MAVLINK_MSG_ID_PING : MAVLink_ping_message, + MAVLINK_MSG_ID_SYSTEM_TIME_UTC : MAVLink_system_time_utc_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : MAVLink_change_operator_control_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : MAVLink_change_operator_control_ack_message, + MAVLINK_MSG_ID_AUTH_KEY : MAVLink_auth_key_message, + MAVLINK_MSG_ID_ACTION_ACK : MAVLink_action_ack_message, + MAVLINK_MSG_ID_ACTION : MAVLink_action_message, + MAVLINK_MSG_ID_SET_MODE : MAVLink_set_mode_message, + MAVLINK_MSG_ID_SET_NAV_MODE : MAVLink_set_nav_mode_message, + MAVLINK_MSG_ID_PARAM_REQUEST_READ : MAVLink_param_request_read_message, + MAVLINK_MSG_ID_PARAM_REQUEST_LIST : MAVLink_param_request_list_message, + MAVLINK_MSG_ID_PARAM_VALUE : MAVLink_param_value_message, + MAVLINK_MSG_ID_PARAM_SET : MAVLink_param_set_message, + MAVLINK_MSG_ID_GPS_RAW_INT : MAVLink_gps_raw_int_message, + MAVLINK_MSG_ID_SCALED_IMU : MAVLink_scaled_imu_message, + MAVLINK_MSG_ID_GPS_STATUS : MAVLink_gps_status_message, + MAVLINK_MSG_ID_RAW_IMU : MAVLink_raw_imu_message, + MAVLINK_MSG_ID_RAW_PRESSURE : MAVLink_raw_pressure_message, + MAVLINK_MSG_ID_SCALED_PRESSURE : MAVLink_scaled_pressure_message, + MAVLINK_MSG_ID_ATTITUDE : MAVLink_attitude_message, + MAVLINK_MSG_ID_LOCAL_POSITION : MAVLink_local_position_message, + MAVLINK_MSG_ID_GLOBAL_POSITION : MAVLink_global_position_message, + MAVLINK_MSG_ID_GPS_RAW : MAVLink_gps_raw_message, + MAVLINK_MSG_ID_SYS_STATUS : MAVLink_sys_status_message, + MAVLINK_MSG_ID_RC_CHANNELS_RAW : MAVLink_rc_channels_raw_message, + MAVLINK_MSG_ID_RC_CHANNELS_SCALED : MAVLink_rc_channels_scaled_message, + MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : MAVLink_servo_output_raw_message, + MAVLINK_MSG_ID_WAYPOINT : MAVLink_waypoint_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST : MAVLink_waypoint_request_message, + MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : MAVLink_waypoint_set_current_message, + MAVLINK_MSG_ID_WAYPOINT_CURRENT : MAVLink_waypoint_current_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : MAVLink_waypoint_request_list_message, + MAVLINK_MSG_ID_WAYPOINT_COUNT : MAVLink_waypoint_count_message, + MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : MAVLink_waypoint_clear_all_message, + MAVLINK_MSG_ID_WAYPOINT_REACHED : MAVLink_waypoint_reached_message, + MAVLINK_MSG_ID_WAYPOINT_ACK : MAVLink_waypoint_ack_message, + MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : MAVLink_gps_set_global_origin_message, + MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : MAVLink_gps_local_origin_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : MAVLink_local_position_setpoint_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : MAVLink_local_position_setpoint_message, + MAVLINK_MSG_ID_CONTROL_STATUS : MAVLink_control_status_message, + MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : MAVLink_safety_set_allowed_area_message, + MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : MAVLink_safety_allowed_area_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : MAVLink_set_roll_pitch_yaw_thrust_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : MAVLink_set_roll_pitch_yaw_speed_thrust_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_thrust_setpoint_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, + MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : MAVLink_nav_controller_output_message, + MAVLINK_MSG_ID_POSITION_TARGET : MAVLink_position_target_message, + MAVLINK_MSG_ID_STATE_CORRECTION : MAVLink_state_correction_message, + MAVLINK_MSG_ID_SET_ALTITUDE : MAVLink_set_altitude_message, + MAVLINK_MSG_ID_REQUEST_DATA_STREAM : MAVLink_request_data_stream_message, + MAVLINK_MSG_ID_HIL_STATE : MAVLink_hil_state_message, + MAVLINK_MSG_ID_HIL_CONTROLS : MAVLink_hil_controls_message, + MAVLINK_MSG_ID_MANUAL_CONTROL : MAVLink_manual_control_message, + MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : MAVLink_rc_channels_override_message, + MAVLINK_MSG_ID_GLOBAL_POSITION_INT : MAVLink_global_position_int_message, + MAVLINK_MSG_ID_VFR_HUD : MAVLink_vfr_hud_message, + MAVLINK_MSG_ID_COMMAND : MAVLink_command_message, + MAVLINK_MSG_ID_COMMAND_ACK : MAVLink_command_ack_message, + MAVLINK_MSG_ID_OPTICAL_FLOW : MAVLink_optical_flow_message, + MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : MAVLink_object_detection_event_message, + MAVLINK_MSG_ID_DEBUG_VECT : MAVLink_debug_vect_message, + MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : MAVLink_named_value_float_message, + MAVLINK_MSG_ID_NAMED_VALUE_INT : MAVLink_named_value_int_message, + MAVLINK_MSG_ID_STATUSTEXT : MAVLink_statustext_message, + MAVLINK_MSG_ID_DEBUG : MAVLink_debug_message, +} + +class MAVError(Exception): + '''MAVLink error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + +class MAVString(str): + '''NUL terminated string''' + def __init__(self, s): + str.__init__(self) + def __str__(self): + i = self.find(chr(0)) + if i == -1: + return self[:] + return self[0:i] + +class MAVLink_bad_data(MAVLink_message): + ''' + a piece of bad data in a mavlink stream + ''' + def __init__(self, data, reason): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') + self._fieldnames = ['data', 'reason'] + self.data = data + self.reason = reason + self._msgbuf = data + + def __str__(self): + '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' + return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) + +class MAVLink(object): + '''MAVLink protocol handling class''' + def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): + self.seq = 0 + self.file = file + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.callback = None + self.callback_args = None + self.callback_kwargs = None + self.send_callback = None + self.send_callback_args = None + self.send_callback_kwargs = None + self.buf = bytearray() + self.expected_length = 8 + self.have_prefix_error = False + self.robust_parsing = False + self.protocol_marker = 85 + self.little_endian = False + self.crc_extra = False + self.sort_fields = False + self.total_packets_sent = 0 + self.total_bytes_sent = 0 + self.total_packets_received = 0 + self.total_bytes_received = 0 + self.total_receive_errors = 0 + self.startup_time = time.time() + if native_supported and (use_native or native_testing or native_force): + print("NOTE: mavnative is currently beta-test code") + self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) + else: + self.native = None + if native_testing: + self.test_buf = bytearray() + + def set_callback(self, callback, *args, **kwargs): + self.callback = callback + self.callback_args = args + self.callback_kwargs = kwargs + + def set_send_callback(self, callback, *args, **kwargs): + self.send_callback = callback + self.send_callback_args = args + self.send_callback_kwargs = kwargs + + def send(self, mavmsg): + '''send a MAVLink message''' + buf = mavmsg.pack(self) + self.file.write(buf) + self.seq = (self.seq + 1) % 256 + self.total_packets_sent += 1 + self.total_bytes_sent += len(buf) + if self.send_callback: + self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) + + def bytes_needed(self): + '''return number of bytes needed for next parsing stage''' + if self.native: + ret = self.native.expected_length - len(self.buf) + else: + ret = self.expected_length - len(self.buf) + + if ret <= 0: + return 1 + return ret + + def __parse_char_native(self, c): + '''this method exists only to see in profiling results''' + m = self.native.parse_chars(c) + return m + + def __callbacks(self, msg): + '''this method exists only to make profiling results easier to read''' + if self.callback: + self.callback(msg, *self.callback_args, **self.callback_kwargs) + + def parse_char(self, c): + '''input some data bytes, possibly returning a new message''' + self.buf.extend(c) + + self.total_bytes_received += len(c) + + if self.native: + if native_testing: + self.test_buf.extend(c) + m = self.__parse_char_native(self.test_buf) + m2 = self.__parse_char_legacy() + if m2 != m: + print("Native: %s\nLegacy: %s\n" % (m, m2)) + raise Exception('Native vs. Legacy mismatch') + else: + m = self.__parse_char_native(self.buf) + else: + m = self.__parse_char_legacy() + + if m != None: + self.total_packets_received += 1 + self.__callbacks(m) + + return m + + def __parse_char_legacy(self): + '''input some data bytes, possibly returning a new message (uses no native code)''' + if len(self.buf) >= 1 and self.buf[0] != 85: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 85: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value) + + def param_set_send(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value)) + + def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature)) + + def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def local_position_encode(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_message(usec, x, y, z, vx, vy, vz) + + def local_position_send(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz)) + + def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz) + + def global_position_send(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz)) + + def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop) + + def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)) + + def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def waypoint_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_request_message(target_system, target_component, seq) + + def waypoint_request_send(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_request_encode(target_system, target_component, seq)) + + def waypoint_set_current_encode(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_set_current_message(target_system, target_component, seq) + + def waypoint_set_current_send(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_set_current_encode(target_system, target_component, seq)) + + def waypoint_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_current_message(seq) + + def waypoint_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_current_encode(seq)) + + def waypoint_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_request_list_message(target_system, target_component) + + def waypoint_request_list_send(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_request_list_encode(target_system, target_component)) + + def waypoint_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return MAVLink_waypoint_count_message(target_system, target_component, count) + + def waypoint_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return self.send(self.waypoint_count_encode(target_system, target_component, count)) + + def waypoint_clear_all_encode(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_clear_all_message(target_system, target_component) + + def waypoint_clear_all_send(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_clear_all_encode(target_system, target_component)) + + def waypoint_reached_encode(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_reached_message(seq) + + def waypoint_reached_send(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_reached_encode(seq)) + + def waypoint_ack_encode(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return MAVLink_waypoint_ack_message(target_system, target_component, type) + + def waypoint_ack_send(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return self.send(self.waypoint_ack_encode(target_system, target_component, type)) + + def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude) + + def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude)) + + def gps_local_origin_set_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return MAVLink_gps_local_origin_set_message(latitude, longitude, altitude) + + def gps_local_origin_set_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude)) + + def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw) + + def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw)) + + def local_position_setpoint_encode(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_message(x, y, z, yaw) + + def local_position_setpoint_send(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_encode(x, y, z, yaw)) + + def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw) + + def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) + + def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) + + def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) + + def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) + + def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust) + + def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust)) + + def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust) + + def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def position_target_encode(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return MAVLink_position_target_message(x, y, z, yaw) + + def position_target_send(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return self.send(self.position_target_encode(x, y, z, yaw)) + + def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) + + def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) + + def set_altitude_encode(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return MAVLink_set_altitude_message(target, mode) + + def set_altitude_send(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return self.send(self.set_altitude_encode(target, mode)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode) + + def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)) + + def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) + + def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def global_position_int_encode(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz) + + def global_position_int_send(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4) + + def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance) + + def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance)) + + def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance) + + def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance)) + + def debug_vect_encode(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, usec, x, y, z) + + def debug_vect_send(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, usec, x, y, z)) + + def named_value_float_encode(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(name, value) + + def named_value_float_send(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(name, value)) + + def named_value_int_encode(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(name, value) + + def named_value_int_send(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(ind, value) + + def debug_send(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(ind, value)) + diff --git a/pymavlink/dialects/v09/slugs.xml b/pymavlink/dialects/v09/slugs.xml new file mode 100644 index 0000000..db08abb --- /dev/null +++ b/pymavlink/dialects/v09/slugs.xml @@ -0,0 +1,148 @@ + + + common.xml + + + + + + + + Sensor and DSC control loads. + + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + + Air data for altitude and airspeed computation. + + Dynamic pressure (Pa) + Static pressure (Pa) + Board temperature + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the Nav Filter + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Visible sattelites reported by Gps + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + The system setting the commands + Commanded Airspeed + Log value 2 + Log value 3 + + + + + This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + The system setting the commands + Bitfield containing the PT configuration + + + + + + Action messages focused on the SLUGS AP. + The system reporting the action + Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + Value associated with the action + + + + diff --git a/pymavlink/dialects/v09/test.py b/pymavlink/dialects/v09/test.py new file mode 100644 index 0000000..998cab5 --- /dev/null +++ b/pymavlink/dialects/v09/test.py @@ -0,0 +1,536 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: test.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "0.9" +DIALECT = "test" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 85, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if False: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack('ccBHIQbhiqfdBHIQbhiqfd', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3] + array_lengths = [0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3] + crc_extra = 91 + + def __init__(self, c, s, u8, u16, u32, u64, s8, s16, s32, s64, f, d, u8_array, u16_array, u32_array, u64_array, s8_array, s16_array, s32_array, s64_array, f_array, d_array): + MAVLink_message.__init__(self, MAVLink_test_types_message.id, MAVLink_test_types_message.name) + self._fieldnames = MAVLink_test_types_message.fieldnames + self.c = c + self.s = s + self.u8 = u8 + self.u16 = u16 + self.u32 = u32 + self.u64 = u64 + self.s8 = s8 + self.s16 = s16 + self.s32 = s32 + self.s64 = s64 + self.f = f + self.d = d + self.u8_array = u8_array + self.u16_array = u16_array + self.u32_array = u32_array + self.u64_array = u64_array + self.s8_array = s8_array + self.s16_array = s16_array + self.s32_array = s32_array + self.s64_array = s64_array + self.f_array = f_array + self.d_array = d_array + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 91, struct.pack('>c10sBHIQbhiqfd3B3H3I3Q3b3h3i3q3f3d', self.c, self.s, self.u8, self.u16, self.u32, self.u64, self.s8, self.s16, self.s32, self.s64, self.f, self.d, self.u8_array[0], self.u8_array[1], self.u8_array[2], self.u16_array[0], self.u16_array[1], self.u16_array[2], self.u32_array[0], self.u32_array[1], self.u32_array[2], self.u64_array[0], self.u64_array[1], self.u64_array[2], self.s8_array[0], self.s8_array[1], self.s8_array[2], self.s16_array[0], self.s16_array[1], self.s16_array[2], self.s32_array[0], self.s32_array[1], self.s32_array[2], self.s64_array[0], self.s64_array[1], self.s64_array[2], self.f_array[0], self.f_array[1], self.f_array[2], self.d_array[0], self.d_array[1], self.d_array[2])) + + +mavlink_map = { + MAVLINK_MSG_ID_TEST_TYPES : MAVLink_test_types_message, +} + +class MAVError(Exception): + '''MAVLink error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + +class MAVString(str): + '''NUL terminated string''' + def __init__(self, s): + str.__init__(self) + def __str__(self): + i = self.find(chr(0)) + if i == -1: + return self[:] + return self[0:i] + +class MAVLink_bad_data(MAVLink_message): + ''' + a piece of bad data in a mavlink stream + ''' + def __init__(self, data, reason): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') + self._fieldnames = ['data', 'reason'] + self.data = data + self.reason = reason + self._msgbuf = data + + def __str__(self): + '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' + return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) + +class MAVLink(object): + '''MAVLink protocol handling class''' + def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): + self.seq = 0 + self.file = file + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.callback = None + self.callback_args = None + self.callback_kwargs = None + self.send_callback = None + self.send_callback_args = None + self.send_callback_kwargs = None + self.buf = bytearray() + self.expected_length = 8 + self.have_prefix_error = False + self.robust_parsing = False + self.protocol_marker = 85 + self.little_endian = False + self.crc_extra = False + self.sort_fields = False + self.total_packets_sent = 0 + self.total_bytes_sent = 0 + self.total_packets_received = 0 + self.total_bytes_received = 0 + self.total_receive_errors = 0 + self.startup_time = time.time() + if native_supported and (use_native or native_testing or native_force): + print("NOTE: mavnative is currently beta-test code") + self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) + else: + self.native = None + if native_testing: + self.test_buf = bytearray() + + def set_callback(self, callback, *args, **kwargs): + self.callback = callback + self.callback_args = args + self.callback_kwargs = kwargs + + def set_send_callback(self, callback, *args, **kwargs): + self.send_callback = callback + self.send_callback_args = args + self.send_callback_kwargs = kwargs + + def send(self, mavmsg): + '''send a MAVLink message''' + buf = mavmsg.pack(self) + self.file.write(buf) + self.seq = (self.seq + 1) % 256 + self.total_packets_sent += 1 + self.total_bytes_sent += len(buf) + if self.send_callback: + self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) + + def bytes_needed(self): + '''return number of bytes needed for next parsing stage''' + if self.native: + ret = self.native.expected_length - len(self.buf) + else: + ret = self.expected_length - len(self.buf) + + if ret <= 0: + return 1 + return ret + + def __parse_char_native(self, c): + '''this method exists only to see in profiling results''' + m = self.native.parse_chars(c) + return m + + def __callbacks(self, msg): + '''this method exists only to make profiling results easier to read''' + if self.callback: + self.callback(msg, *self.callback_args, **self.callback_kwargs) + + def parse_char(self, c): + '''input some data bytes, possibly returning a new message''' + self.buf.extend(c) + + self.total_bytes_received += len(c) + + if self.native: + if native_testing: + self.test_buf.extend(c) + m = self.__parse_char_native(self.test_buf) + m2 = self.__parse_char_legacy() + if m2 != m: + print("Native: %s\nLegacy: %s\n" % (m, m2)) + raise Exception('Native vs. Legacy mismatch') + else: + m = self.__parse_char_native(self.buf) + else: + m = self.__parse_char_legacy() + + if m != None: + self.total_packets_received += 1 + self.__callbacks(m) + + return m + + def __parse_char_legacy(self): + '''input some data bytes, possibly returning a new message (uses no native code)''' + if len(self.buf) >= 1 and self.buf[0] != 85: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 85: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/pymavlink/dialects/v09/ualberta.py b/pymavlink/dialects/v09/ualberta.py new file mode 100644 index 0000000..fcce62d --- /dev/null +++ b/pymavlink/dialects/v09/ualberta.py @@ -0,0 +1,5339 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: ualberta.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "0.9" +DIALECT = "ualberta" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 85, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if False: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at waypoint (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this waypoint an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this waypoint an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this waypoint for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this waypoint for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this waypoint for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this waypoint for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Empty''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system to + # control the vehicle attitude and the + # attitude of various sensors such + # as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Empty''' +enums['MAV_CMD'][176].param[3] = '''Empty''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera capturing. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera capturing.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the + # vehicle itself. This can then be used by the + # vehicles control system + # to control the vehicle attitude and the + # attitude of various + # devices such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + ''') +enums['MAV_CMD'][201].param[1] = '''Region of interest mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''Waypoint index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple cameras etc.)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Empty''' +enums['MAV_CMD'][241].param[6] = '''Empty''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM''' +enums['MAV_CMD'][245].param[3] = '''Reserved''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_ENUM_END = 246 # +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next waypoint. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next waypoint.''') +MAV_ROI_WPINDEX = 2 # Point toward given waypoint. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given waypoint.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_NAV_FILTER_BIAS = 220 +MAVLINK_MSG_ID_RADIO_CALIBRATION = 221 +MAVLINK_MSG_ID_UALBERTA_SYS_STATUS = 222 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_BOOT = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 3 +MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_ACTION_ACK = 9 +MAVLINK_MSG_ID_ACTION = 10 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_SET_NAV_MODE = 12 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_GPS_STATUS = 27 +MAVLINK_MSG_ID_RAW_IMU = 28 +MAVLINK_MSG_ID_RAW_PRESSURE = 29 +MAVLINK_MSG_ID_SCALED_PRESSURE = 38 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_LOCAL_POSITION = 31 +MAVLINK_MSG_ID_GLOBAL_POSITION = 33 +MAVLINK_MSG_ID_GPS_RAW = 32 +MAVLINK_MSG_ID_SYS_STATUS = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37 +MAVLINK_MSG_ID_WAYPOINT = 39 +MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40 +MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41 +MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42 +MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43 +MAVLINK_MSG_ID_WAYPOINT_COUNT = 44 +MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45 +MAVLINK_MSG_ID_WAYPOINT_REACHED = 46 +MAVLINK_MSG_ID_WAYPOINT_ACK = 47 +MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50 +MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51 +MAVLINK_MSG_ID_CONTROL_STATUS = 52 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55 +MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57 +MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_POSITION_TARGET = 63 +MAVLINK_MSG_ID_STATE_CORRECTION = 64 +MAVLINK_MSG_ID_SET_ALTITUDE = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_HIL_STATE = 67 +MAVLINK_MSG_ID_HIL_CONTROLS = 68 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND = 75 +MAVLINK_MSG_ID_COMMAND_ACK = 76 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140 +MAVLINK_MSG_ID_DEBUG_VECT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 253 +MAVLINK_MSG_ID_STATUSTEXT = 254 +MAVLINK_MSG_ID_DEBUG = 255 + +class MAVLink_nav_filter_bias_message(MAVLink_message): + ''' + Accelerometer and Gyro biases from the navigation filter + ''' + id = MAVLINK_MSG_ID_NAV_FILTER_BIAS + name = 'NAV_FILTER_BIAS' + fieldnames = ['usec', 'accel_0', 'accel_1', 'accel_2', 'gyro_0', 'gyro_1', 'gyro_2'] + ordered_fieldnames = [ 'usec', 'accel_0', 'accel_1', 'accel_2', 'gyro_0', 'gyro_1', 'gyro_2' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 34 + + def __init__(self, usec, accel_0, accel_1, accel_2, gyro_0, gyro_1, gyro_2): + MAVLink_message.__init__(self, MAVLink_nav_filter_bias_message.id, MAVLink_nav_filter_bias_message.name) + self._fieldnames = MAVLink_nav_filter_bias_message.fieldnames + self.usec = usec + self.accel_0 = accel_0 + self.accel_1 = accel_1 + self.accel_2 = accel_2 + self.gyro_0 = gyro_0 + self.gyro_1 = gyro_1 + self.gyro_2 = gyro_2 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 34, struct.pack('>Qffffff', self.usec, self.accel_0, self.accel_1, self.accel_2, self.gyro_0, self.gyro_1, self.gyro_2)) + +class MAVLink_radio_calibration_message(MAVLink_message): + ''' + Complete set of calibration parameters for the radio + ''' + id = MAVLINK_MSG_ID_RADIO_CALIBRATION + name = 'RADIO_CALIBRATION' + fieldnames = ['aileron', 'elevator', 'rudder', 'gyro', 'pitch', 'throttle'] + ordered_fieldnames = [ 'aileron', 'elevator', 'rudder', 'gyro', 'pitch', 'throttle' ] + format = '>3H3H3H2H5H5H' + native_format = bytearray('>HHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [3, 3, 3, 2, 5, 5] + array_lengths = [3, 3, 3, 2, 5, 5] + crc_extra = 71 + + def __init__(self, aileron, elevator, rudder, gyro, pitch, throttle): + MAVLink_message.__init__(self, MAVLink_radio_calibration_message.id, MAVLink_radio_calibration_message.name) + self._fieldnames = MAVLink_radio_calibration_message.fieldnames + self.aileron = aileron + self.elevator = elevator + self.rudder = rudder + self.gyro = gyro + self.pitch = pitch + self.throttle = throttle + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 71, struct.pack('>3H3H3H2H5H5H', self.aileron[0], self.aileron[1], self.aileron[2], self.elevator[0], self.elevator[1], self.elevator[2], self.rudder[0], self.rudder[1], self.rudder[2], self.gyro[0], self.gyro[1], self.pitch[0], self.pitch[1], self.pitch[2], self.pitch[3], self.pitch[4], self.throttle[0], self.throttle[1], self.throttle[2], self.throttle[3], self.throttle[4])) + +class MAVLink_ualberta_sys_status_message(MAVLink_message): + ''' + System status specific to ualberta uav + ''' + id = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS + name = 'UALBERTA_SYS_STATUS' + fieldnames = ['mode', 'nav_mode', 'pilot'] + ordered_fieldnames = [ 'mode', 'nav_mode', 'pilot' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 15 + + def __init__(self, mode, nav_mode, pilot): + MAVLink_message.__init__(self, MAVLink_ualberta_sys_status_message.id, MAVLink_ualberta_sys_status_message.name) + self._fieldnames = MAVLink_ualberta_sys_status_message.fieldnames + self.mode = mode + self.nav_mode = nav_mode + self.pilot = pilot + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 15, struct.pack('>BBB', self.mode, self.nav_mode, self.pilot)) + +class MAVLink_heartbeat_message(MAVLink_message): + ''' + The heartbeat message shows that a system is present and + responding. The type of the MAV and Autopilot hardware allow + the receiving system to treat further messages from this + system appropriate (e.g. by laying out the user interface + based on the autopilot). + ''' + id = MAVLINK_MSG_ID_HEARTBEAT + name = 'HEARTBEAT' + fieldnames = ['type', 'autopilot', 'mavlink_version'] + ordered_fieldnames = [ 'type', 'autopilot', 'mavlink_version' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 72 + + def __init__(self, type, autopilot, mavlink_version): + MAVLink_message.__init__(self, MAVLink_heartbeat_message.id, MAVLink_heartbeat_message.name) + self._fieldnames = MAVLink_heartbeat_message.fieldnames + self.type = type + self.autopilot = autopilot + self.mavlink_version = mavlink_version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) + +class MAVLink_boot_message(MAVLink_message): + ''' + The boot message indicates that a system is starting. The + onboard software version allows to keep track of onboard + soft/firmware revisions. + ''' + id = MAVLINK_MSG_ID_BOOT + name = 'BOOT' + fieldnames = ['version'] + ordered_fieldnames = [ 'version' ] + format = '>I' + native_format = bytearray('>I', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 39 + + def __init__(self, version): + MAVLink_message.__init__(self, MAVLink_boot_message.id, MAVLink_boot_message.name) + self._fieldnames = MAVLink_boot_message.fieldnames + self.version = version + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version)) + +class MAVLink_system_time_message(MAVLink_message): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME + name = 'SYSTEM_TIME' + fieldnames = ['time_usec'] + ordered_fieldnames = [ 'time_usec' ] + format = '>Q' + native_format = bytearray('>Q', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 190 + + def __init__(self, time_usec): + MAVLink_message.__init__(self, MAVLink_system_time_message.id, MAVLink_system_time_message.name) + self._fieldnames = MAVLink_system_time_message.fieldnames + self.time_usec = time_usec + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec)) + +class MAVLink_ping_message(MAVLink_message): + ''' + A ping message either requesting or responding to a ping. This + allows to measure the system latencies, including serial port, + radio modem and UDP connections. + ''' + id = MAVLINK_MSG_ID_PING + name = 'PING' + fieldnames = ['seq', 'target_system', 'target_component', 'time'] + ordered_fieldnames = [ 'seq', 'target_system', 'target_component', 'time' ] + format = '>IBBQ' + native_format = bytearray('>IBBQ', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 92 + + def __init__(self, seq, target_system, target_component, time): + MAVLink_message.__init__(self, MAVLink_ping_message.id, MAVLink_ping_message.name) + self._fieldnames = MAVLink_ping_message.fieldnames + self.seq = seq + self.target_system = target_system + self.target_component = target_component + self.time = time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time)) + +class MAVLink_system_time_utc_message(MAVLink_message): + ''' + UTC date and time from GPS module + ''' + id = MAVLINK_MSG_ID_SYSTEM_TIME_UTC + name = 'SYSTEM_TIME_UTC' + fieldnames = ['utc_date', 'utc_time'] + ordered_fieldnames = [ 'utc_date', 'utc_time' ] + format = '>II' + native_format = bytearray('>II', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 191 + + def __init__(self, utc_date, utc_time): + MAVLink_message.__init__(self, MAVLink_system_time_utc_message.id, MAVLink_system_time_utc_message.name) + self._fieldnames = MAVLink_system_time_utc_message.fieldnames + self.utc_date = utc_date + self.utc_time = utc_time + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time)) + +class MAVLink_change_operator_control_message(MAVLink_message): + ''' + Request to control this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL + name = 'CHANGE_OPERATOR_CONTROL' + fieldnames = ['target_system', 'control_request', 'version', 'passkey'] + ordered_fieldnames = [ 'target_system', 'control_request', 'version', 'passkey' ] + format = '>BBB25s' + native_format = bytearray('>BBBc', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 25] + crc_extra = 217 + + def __init__(self, target_system, control_request, version, passkey): + MAVLink_message.__init__(self, MAVLink_change_operator_control_message.id, MAVLink_change_operator_control_message.name) + self._fieldnames = MAVLink_change_operator_control_message.fieldnames + self.target_system = target_system + self.control_request = control_request + self.version = version + self.passkey = passkey + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey)) + +class MAVLink_change_operator_control_ack_message(MAVLink_message): + ''' + Accept / deny control of this MAV + ''' + id = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK + name = 'CHANGE_OPERATOR_CONTROL_ACK' + fieldnames = ['gcs_system_id', 'control_request', 'ack'] + ordered_fieldnames = [ 'gcs_system_id', 'control_request', 'ack' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 104 + + def __init__(self, gcs_system_id, control_request, ack): + MAVLink_message.__init__(self, MAVLink_change_operator_control_ack_message.id, MAVLink_change_operator_control_ack_message.name) + self._fieldnames = MAVLink_change_operator_control_ack_message.fieldnames + self.gcs_system_id = gcs_system_id + self.control_request = control_request + self.ack = ack + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack)) + +class MAVLink_auth_key_message(MAVLink_message): + ''' + Emit an encrypted signature / key identifying this system. + PLEASE NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for true + safety. + ''' + id = MAVLINK_MSG_ID_AUTH_KEY + name = 'AUTH_KEY' + fieldnames = ['key'] + ordered_fieldnames = [ 'key' ] + format = '>32s' + native_format = bytearray('>c', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [32] + crc_extra = 119 + + def __init__(self, key): + MAVLink_message.__init__(self, MAVLink_auth_key_message.id, MAVLink_auth_key_message.name) + self._fieldnames = MAVLink_auth_key_message.fieldnames + self.key = key + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key)) + +class MAVLink_action_ack_message(MAVLink_message): + ''' + This message acknowledges an action. IMPORTANT: The + acknowledgement can be also negative, e.g. the MAV rejects a + reset message because it is in-flight. The action ids are + defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION_ACK + name = 'ACTION_ACK' + fieldnames = ['action', 'result'] + ordered_fieldnames = [ 'action', 'result' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 219 + + def __init__(self, action, result): + MAVLink_message.__init__(self, MAVLink_action_ack_message.id, MAVLink_action_ack_message.name) + self._fieldnames = MAVLink_action_ack_message.fieldnames + self.action = action + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result)) + +class MAVLink_action_message(MAVLink_message): + ''' + An action message allows to execute a certain onboard action. + These include liftoff, land, storing parameters too EEPROM, + shutddown, etc. The action ids are defined in ENUM MAV_ACTION + in mavlink/include/mavlink_types.h + ''' + id = MAVLINK_MSG_ID_ACTION + name = 'ACTION' + fieldnames = ['target', 'target_component', 'action'] + ordered_fieldnames = [ 'target', 'target_component', 'action' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 60 + + def __init__(self, target, target_component, action): + MAVLink_message.__init__(self, MAVLink_action_message.id, MAVLink_action_message.name) + self._fieldnames = MAVLink_action_message.fieldnames + self.target = target + self.target_component = target_component + self.action = action + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action)) + +class MAVLink_set_mode_message(MAVLink_message): + ''' + Set the system mode, as defined by enum MAV_MODE in + mavlink/include/mavlink_types.h. There is no target component + id as the mode is by definition for the overall aircraft, not + only for one component. + ''' + id = MAVLINK_MSG_ID_SET_MODE + name = 'SET_MODE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 186 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_mode_message.id, MAVLink_set_mode_message.name) + self._fieldnames = MAVLink_set_mode_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode)) + +class MAVLink_set_nav_mode_message(MAVLink_message): + ''' + Set the system navigation mode, as defined by enum + MAV_NAV_MODE in mavlink/include/mavlink_types.h. The + navigation mode applies to the whole aircraft and thus all + components. + ''' + id = MAVLINK_MSG_ID_SET_NAV_MODE + name = 'SET_NAV_MODE' + fieldnames = ['target', 'nav_mode'] + ordered_fieldnames = [ 'target', 'nav_mode' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 10 + + def __init__(self, target, nav_mode): + MAVLink_message.__init__(self, MAVLink_set_nav_mode_message.id, MAVLink_set_nav_mode_message.name) + self._fieldnames = MAVLink_set_nav_mode_message.fieldnames + self.target = target + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode)) + +class MAVLink_param_request_read_message(MAVLink_message): + ''' + Request to read the onboard parameter with the param_id string + id. Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_index' ] + format = '>BB15bh' + native_format = bytearray('>BBbh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 89 + + def __init__(self, target_system, target_component, param_id, param_index): + MAVLink_message.__init__(self, MAVLink_param_request_read_message.id, MAVLink_param_request_read_message.name) + self._fieldnames = MAVLink_param_request_read_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15bh', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_index)) + +class MAVLink_param_request_list_message(MAVLink_message): + ''' + Request all parameters of this component. After his request, + all parameters are emitted. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_LIST + name = 'PARAM_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 159 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_param_request_list_message.id, MAVLink_param_request_list_message.name) + self._fieldnames = MAVLink_param_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_param_value_message(MAVLink_message): + ''' + Emit the value of a onboard parameter. The inclusion of + param_count and param_index in the message allows the + recipient to keep track of received parameters and allows him + to re-request missing parameters after a loss or timeout. + ''' + id = MAVLINK_MSG_ID_PARAM_VALUE + name = 'PARAM_VALUE' + fieldnames = ['param_id', 'param_value', 'param_count', 'param_index'] + ordered_fieldnames = [ 'param_id', 'param_value', 'param_count', 'param_index' ] + format = '>15bfHH' + native_format = bytearray('>bfHH', 'ascii') + orders = [0, 1, 2, 3] + lengths = [15, 1, 1, 1] + array_lengths = [15, 0, 0, 0] + crc_extra = 162 + + def __init__(self, param_id, param_value, param_count, param_index): + MAVLink_message.__init__(self, MAVLink_param_value_message.id, MAVLink_param_value_message.name) + self._fieldnames = MAVLink_param_value_message.fieldnames + self.param_id = param_id + self.param_value = param_value + self.param_count = param_count + self.param_index = param_index + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>15bfHH', self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value, self.param_count, self.param_index)) + +class MAVLink_param_set_message(MAVLink_message): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to + default on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents + to EEPROM. IMPORTANT: The receiving component should + acknowledge the new parameter value by sending a param_value + message to all communication partners. This will also ensure + that multiple GCS all have an up-to-date list of all + parameters. If the sending GCS did not receive a PARAM_VALUE + message within its timeout time, it should re-send the + PARAM_SET message. + ''' + id = MAVLINK_MSG_ID_PARAM_SET + name = 'PARAM_SET' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_value'] + ordered_fieldnames = [ 'target_system', 'target_component', 'param_id', 'param_value' ] + format = '>BB15bf' + native_format = bytearray('>BBbf', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 15, 1] + array_lengths = [0, 0, 15, 0] + crc_extra = 121 + + def __init__(self, target_system, target_component, param_id, param_value): + MAVLink_message.__init__(self, MAVLink_param_set_message.id, MAVLink_param_set_message.name) + self._fieldnames = MAVLink_param_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.param_id = param_id + self.param_value = param_value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15bf', self.target_system, self.target_component, self.param_id[0], self.param_id[1], self.param_id[2], self.param_id[3], self.param_id[4], self.param_id[5], self.param_id[6], self.param_id[7], self.param_id[8], self.param_id[9], self.param_id[10], self.param_id[11], self.param_id[12], self.param_id[13], self.param_id[14], self.param_value)) + +class MAVLink_gps_raw_int_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW_INT + name = 'GPS_RAW_INT' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBiiiffff' + native_format = bytearray('>QBiiiffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 149 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_int_message.id, MAVLink_gps_raw_int_message.name) + self._fieldnames = MAVLink_gps_raw_int_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_scaled_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should contain the scaled values to the described + units + ''' + id = MAVLINK_MSG_ID_SCALED_IMU + name = 'SCALED_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 222 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_scaled_imu_message.id, MAVLink_scaled_imu_message.name) + self._fieldnames = MAVLink_scaled_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_gps_status_message(MAVLink_message): + ''' + The positioning status, as reported by GPS. This message is + intended to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION for the + global position estimate. This message can contain information + for up to 20 satellites. + ''' + id = MAVLINK_MSG_ID_GPS_STATUS + name = 'GPS_STATUS' + fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr'] + ordered_fieldnames = [ 'satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr' ] + format = '>B20b20b20b20b20b' + native_format = bytearray('>Bbbbbb', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 20, 20, 20, 20, 20] + array_lengths = [0, 20, 20, 20, 20, 20] + crc_extra = 110 + + def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + MAVLink_message.__init__(self, MAVLink_gps_status_message.id, MAVLink_gps_status_message.name) + self._fieldnames = MAVLink_gps_status_message.fieldnames + self.satellites_visible = satellites_visible + self.satellite_prn = satellite_prn + self.satellite_used = satellite_used + self.satellite_elevation = satellite_elevation + self.satellite_azimuth = satellite_azimuth + self.satellite_snr = satellite_snr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 110, struct.pack('>B20b20b20b20b20b', self.satellites_visible, self.satellite_prn[0], self.satellite_prn[1], self.satellite_prn[2], self.satellite_prn[3], self.satellite_prn[4], self.satellite_prn[5], self.satellite_prn[6], self.satellite_prn[7], self.satellite_prn[8], self.satellite_prn[9], self.satellite_prn[10], self.satellite_prn[11], self.satellite_prn[12], self.satellite_prn[13], self.satellite_prn[14], self.satellite_prn[15], self.satellite_prn[16], self.satellite_prn[17], self.satellite_prn[18], self.satellite_prn[19], self.satellite_used[0], self.satellite_used[1], self.satellite_used[2], self.satellite_used[3], self.satellite_used[4], self.satellite_used[5], self.satellite_used[6], self.satellite_used[7], self.satellite_used[8], self.satellite_used[9], self.satellite_used[10], self.satellite_used[11], self.satellite_used[12], self.satellite_used[13], self.satellite_used[14], self.satellite_used[15], self.satellite_used[16], self.satellite_used[17], self.satellite_used[18], self.satellite_used[19], self.satellite_elevation[0], self.satellite_elevation[1], self.satellite_elevation[2], self.satellite_elevation[3], self.satellite_elevation[4], self.satellite_elevation[5], self.satellite_elevation[6], self.satellite_elevation[7], self.satellite_elevation[8], self.satellite_elevation[9], self.satellite_elevation[10], self.satellite_elevation[11], self.satellite_elevation[12], self.satellite_elevation[13], self.satellite_elevation[14], self.satellite_elevation[15], self.satellite_elevation[16], self.satellite_elevation[17], self.satellite_elevation[18], self.satellite_elevation[19], self.satellite_azimuth[0], self.satellite_azimuth[1], self.satellite_azimuth[2], self.satellite_azimuth[3], self.satellite_azimuth[4], self.satellite_azimuth[5], self.satellite_azimuth[6], self.satellite_azimuth[7], self.satellite_azimuth[8], self.satellite_azimuth[9], self.satellite_azimuth[10], self.satellite_azimuth[11], self.satellite_azimuth[12], self.satellite_azimuth[13], self.satellite_azimuth[14], self.satellite_azimuth[15], self.satellite_azimuth[16], self.satellite_azimuth[17], self.satellite_azimuth[18], self.satellite_azimuth[19], self.satellite_snr[0], self.satellite_snr[1], self.satellite_snr[2], self.satellite_snr[3], self.satellite_snr[4], self.satellite_snr[5], self.satellite_snr[6], self.satellite_snr[7], self.satellite_snr[8], self.satellite_snr[9], self.satellite_snr[10], self.satellite_snr[11], self.satellite_snr[12], self.satellite_snr[13], self.satellite_snr[14], self.satellite_snr[15], self.satellite_snr[16], self.satellite_snr[17], self.satellite_snr[18], self.satellite_snr[19])) + +class MAVLink_raw_imu_message(MAVLink_message): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This + message should always contain the true raw values without any + scaling to allow data capture and system debugging. + ''' + id = MAVLINK_MSG_ID_RAW_IMU + name = 'RAW_IMU' + fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] + ordered_fieldnames = [ 'usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag' ] + format = '>Qhhhhhhhhh' + native_format = bytearray('>Qhhhhhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 179 + + def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + MAVLink_message.__init__(self, MAVLink_raw_imu_message.id, MAVLink_raw_imu_message.name) + self._fieldnames = MAVLink_raw_imu_message.fieldnames + self.usec = usec + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + self.xgyro = xgyro + self.ygyro = ygyro + self.zgyro = zgyro + self.xmag = xmag + self.ymag = ymag + self.zmag = zmag + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) + +class MAVLink_raw_pressure_message(MAVLink_message): + ''' + The RAW pressure readings for the typical setup of one + absolute pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + ''' + id = MAVLINK_MSG_ID_RAW_PRESSURE + name = 'RAW_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature' ] + format = '>Qhhhh' + native_format = bytearray('>Qhhhh', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 136 + + def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature): + MAVLink_message.__init__(self, MAVLink_raw_pressure_message.id, MAVLink_raw_pressure_message.name) + self._fieldnames = MAVLink_raw_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff1 = press_diff1 + self.press_diff2 = press_diff2 + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature)) + +class MAVLink_scaled_pressure_message(MAVLink_message): + ''' + The pressure readings for the typical setup of one absolute + and differential pressure sensor. The units are as specified + in each field. + ''' + id = MAVLINK_MSG_ID_SCALED_PRESSURE + name = 'SCALED_PRESSURE' + fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature'] + ordered_fieldnames = [ 'usec', 'press_abs', 'press_diff', 'temperature' ] + format = '>Qffh' + native_format = bytearray('>Qffh', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 229 + + def __init__(self, usec, press_abs, press_diff, temperature): + MAVLink_message.__init__(self, MAVLink_scaled_pressure_message.id, MAVLink_scaled_pressure_message.name) + self._fieldnames = MAVLink_scaled_pressure_message.fieldnames + self.usec = usec + self.press_abs = press_abs + self.press_diff = press_diff + self.temperature = temperature + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature)) + +class MAVLink_attitude_message(MAVLink_message): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, + X-front, Y-right). + ''' + id = MAVLINK_MSG_ID_ATTITUDE + name = 'ATTITUDE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 66 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + MAVLink_message.__init__(self, MAVLink_attitude_message.id, MAVLink_attitude_message.name) + self._fieldnames = MAVLink_attitude_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed)) + +class MAVLink_local_position_message(MAVLink_message): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, Z-axis down + (aeronautical frame) + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION + name = 'LOCAL_POSITION' + fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'x', 'y', 'z', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, usec, x, y, z, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_local_position_message.id, MAVLink_local_position_message.name) + self._fieldnames = MAVLink_local_position_message.fieldnames + self.usec = usec + self.x = x + self.y = y + self.z = z + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz)) + +class MAVLink_global_position_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). Coordinate frame is right-handed, Z-axis up + (GPS frame) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION + name = 'GLOBAL_POSITION' + fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>Qffffff' + native_format = bytearray('>Qffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 147 + + def __init__(self, usec, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_message.id, MAVLink_global_position_message.name) + self._fieldnames = MAVLink_global_position_message.fieldnames + self.usec = usec + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_gps_raw_message(MAVLink_message): + ''' + The global position, as returned by the Global Positioning + System (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. Coordinate + frame is right-handed, Z-axis up (GPS frame) + ''' + id = MAVLINK_MSG_ID_GPS_RAW + name = 'GPS_RAW' + fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] + ordered_fieldnames = [ 'usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg' ] + format = '>QBfffffff' + native_format = bytearray('>QBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 185 + + def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + MAVLink_message.__init__(self, MAVLink_gps_raw_message.id, MAVLink_gps_raw_message.name) + self._fieldnames = MAVLink_gps_raw_message.fieldnames + self.usec = usec + self.fix_type = fix_type + self.lat = lat + self.lon = lon + self.alt = alt + self.eph = eph + self.epv = epv + self.v = v + self.hdg = hdg + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) + +class MAVLink_sys_status_message(MAVLink_message): + ''' + The general system state. If the system is following the + MAVLink standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is either + LOCKED (motors shut down and locked), MANUAL (system under RC + control), GUIDED (system with autonomous position control, + position setpoint controlled manually) or AUTO (system guided + by path/waypoint planner). The NAV_MODE defined the current + flight state: LIFTOFF (often an open-loop maneuver), LANDING, + WAYPOINTS or VECTOR. This represents the internal navigation + state machine. The system status shows wether the system is + currently active or not and if an emergency occured. During + the CRITICAL and EMERGENCY states the MAV is still considered + to be active, but should start emergency procedures + autonomously. After a failure occured it should first move + from active to critical to allow manual intervention and then + move to emergency after a certain timeout. + ''' + id = MAVLINK_MSG_ID_SYS_STATUS + name = 'SYS_STATUS' + fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop'] + ordered_fieldnames = [ 'mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop' ] + format = '>BBBHHHH' + native_format = bytearray('>BBBHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 112 + + def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + MAVLink_message.__init__(self, MAVLink_sys_status_message.id, MAVLink_sys_status_message.name) + self._fieldnames = MAVLink_sys_status_message.fieldnames + self.mode = mode + self.nav_mode = nav_mode + self.status = status + self.load = load + self.vbat = vbat + self.battery_remaining = battery_remaining + self.packet_drop = packet_drop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop)) + +class MAVLink_rc_channels_raw_message(MAVLink_message): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_RAW + name = 'RC_CHANNELS_RAW' + fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi'] + ordered_fieldnames = [ 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi' ] + format = '>HHHHHHHHB' + native_format = bytearray('>HHHHHHHHB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 252 + + def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_raw_message.id, MAVLink_rc_channels_raw_message.name) + self._fieldnames = MAVLink_rc_channels_raw_message.fieldnames + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi)) + +class MAVLink_rc_channels_scaled_message(MAVLink_message): + ''' + The scaled values of the RC channels received. (-100%) -10000, + (0%) 0, (100%) 10000 + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_SCALED + name = 'RC_CHANNELS_SCALED' + fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi'] + ordered_fieldnames = [ 'chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi' ] + format = '>hhhhhhhhB' + native_format = bytearray('>hhhhhhhhB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 162 + + def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + MAVLink_message.__init__(self, MAVLink_rc_channels_scaled_message.id, MAVLink_rc_channels_scaled_message.name) + self._fieldnames = MAVLink_rc_channels_scaled_message.fieldnames + self.chan1_scaled = chan1_scaled + self.chan2_scaled = chan2_scaled + self.chan3_scaled = chan3_scaled + self.chan4_scaled = chan4_scaled + self.chan5_scaled = chan5_scaled + self.chan6_scaled = chan6_scaled + self.chan7_scaled = chan7_scaled + self.chan8_scaled = chan8_scaled + self.rssi = rssi + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi)) + +class MAVLink_servo_output_raw_message(MAVLink_message): + ''' + The RAW values of the servo outputs (for RC input from the + remote, use the RC_CHANNELS messages). The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + ''' + id = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW + name = 'SERVO_OUTPUT_RAW' + fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw'] + ordered_fieldnames = [ 'servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw' ] + format = '>HHHHHHHH' + native_format = bytearray('>HHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + MAVLink_message.__init__(self, MAVLink_servo_output_raw_message.id, MAVLink_servo_output_raw_message.name) + self._fieldnames = MAVLink_servo_output_raw_message.fieldnames + self.servo1_raw = servo1_raw + self.servo2_raw = servo2_raw + self.servo3_raw = servo3_raw + self.servo4_raw = servo4_raw + self.servo5_raw = servo5_raw + self.servo6_raw = servo6_raw + self.servo7_raw = servo7_raw + self.servo8_raw = servo8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw)) + +class MAVLink_waypoint_message(MAVLink_message): + ''' + Message encoding a waypoint. This message is emitted to + announce the presence of a waypoint and to set a waypoint + on the system. The waypoint can be either in x, y, z meters + (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is + Z-down, right handed, global frame is Z-up, right handed + ''' + id = MAVLINK_MSG_ID_WAYPOINT + name = 'WAYPOINT' + fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z' ] + format = '>BBHBBBBfffffff' + native_format = bytearray('>BBHBBBBfffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 128 + + def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + MAVLink_message.__init__(self, MAVLink_waypoint_message.id, MAVLink_waypoint_message.name) + self._fieldnames = MAVLink_waypoint_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + self.frame = frame + self.command = command + self.current = current + self.autocontinue = autocontinue + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z)) + +class MAVLink_waypoint_request_message(MAVLink_message): + ''' + Request the information of the waypoint with the sequence + number seq. The response of the system to this message should + be a WAYPOINT message. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST + name = 'WAYPOINT_REQUEST' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 9 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_request_message.id, MAVLink_waypoint_request_message.name) + self._fieldnames = MAVLink_waypoint_request_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_set_current_message(MAVLink_message): + ''' + Set the waypoint with sequence number seq as current waypoint. + This means that the MAV will continue to this waypoint on the + shortest path (not following the waypoints in-between). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT + name = 'WAYPOINT_SET_CURRENT' + fieldnames = ['target_system', 'target_component', 'seq'] + ordered_fieldnames = [ 'target_system', 'target_component', 'seq' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 106 + + def __init__(self, target_system, target_component, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_set_current_message.id, MAVLink_waypoint_set_current_message.name) + self._fieldnames = MAVLink_waypoint_set_current_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) + +class MAVLink_waypoint_current_message(MAVLink_message): + ''' + Message that announces the sequence number of the current + active waypoint. The MAV will fly towards this waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CURRENT + name = 'WAYPOINT_CURRENT' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 101 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_current_message.id, MAVLink_waypoint_current_message.name) + self._fieldnames = MAVLink_waypoint_current_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_request_list_message(MAVLink_message): + ''' + Request the overall list of waypoints from the + system/component. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST + name = 'WAYPOINT_REQUEST_LIST' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_request_list_message.id, MAVLink_waypoint_request_list_message.name) + self._fieldnames = MAVLink_waypoint_request_list_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_count_message(MAVLink_message): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST + by the MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of waypoints. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_COUNT + name = 'WAYPOINT_COUNT' + fieldnames = ['target_system', 'target_component', 'count'] + ordered_fieldnames = [ 'target_system', 'target_component', 'count' ] + format = '>BBH' + native_format = bytearray('>BBH', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 4 + + def __init__(self, target_system, target_component, count): + MAVLink_message.__init__(self, MAVLink_waypoint_count_message.id, MAVLink_waypoint_count_message.name) + self._fieldnames = MAVLink_waypoint_count_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.count = count + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count)) + +class MAVLink_waypoint_clear_all_message(MAVLink_message): + ''' + Delete all waypoints at once. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL + name = 'WAYPOINT_CLEAR_ALL' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = '>BB' + native_format = bytearray('>BB', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 229 + + def __init__(self, target_system, target_component): + MAVLink_message.__init__(self, MAVLink_waypoint_clear_all_message.id, MAVLink_waypoint_clear_all_message.name) + self._fieldnames = MAVLink_waypoint_clear_all_message.fieldnames + self.target_system = target_system + self.target_component = target_component + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component)) + +class MAVLink_waypoint_reached_message(MAVLink_message): + ''' + A certain waypoint has been reached. The system will either + hold this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next waypoint. + ''' + id = MAVLINK_MSG_ID_WAYPOINT_REACHED + name = 'WAYPOINT_REACHED' + fieldnames = ['seq'] + ordered_fieldnames = [ 'seq' ] + format = '>H' + native_format = bytearray('>H', 'ascii') + orders = [0] + lengths = [1] + array_lengths = [0] + crc_extra = 21 + + def __init__(self, seq): + MAVLink_message.__init__(self, MAVLink_waypoint_reached_message.id, MAVLink_waypoint_reached_message.name) + self._fieldnames = MAVLink_waypoint_reached_message.fieldnames + self.seq = seq + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq)) + +class MAVLink_waypoint_ack_message(MAVLink_message): + ''' + Ack message during waypoint handling. The type field states if + this message is a positive ack (type=0) or if an error + happened (type=non-zero). + ''' + id = MAVLINK_MSG_ID_WAYPOINT_ACK + name = 'WAYPOINT_ACK' + fieldnames = ['target_system', 'target_component', 'type'] + ordered_fieldnames = [ 'target_system', 'target_component', 'type' ] + format = '>BBB' + native_format = bytearray('>BBB', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 214 + + def __init__(self, target_system, target_component, type): + MAVLink_message.__init__(self, MAVLink_waypoint_ack_message.id, MAVLink_waypoint_ack_message.name) + self._fieldnames = MAVLink_waypoint_ack_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.type = type + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type)) + +class MAVLink_gps_set_global_origin_message(MAVLink_message): + ''' + As local waypoints exist, the global waypoint reference allows + to transform between the local coordinate frame and the global + (GPS) coordinate frame. This can be necessary when e.g. in- + and outdoor settings are connected and the MAV should move + from in- to outdoor. + ''' + id = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN + name = 'GPS_SET_GLOBAL_ORIGIN' + fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'target_system', 'target_component', 'latitude', 'longitude', 'altitude' ] + format = '>BBiii' + native_format = bytearray('>BBiii', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 215 + + def __init__(self, target_system, target_component, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_set_global_origin_message.id, MAVLink_gps_set_global_origin_message.name) + self._fieldnames = MAVLink_gps_set_global_origin_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude)) + +class MAVLink_gps_local_origin_set_message(MAVLink_message): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + ''' + id = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET + name = 'GPS_LOCAL_ORIGIN_SET' + fieldnames = ['latitude', 'longitude', 'altitude'] + ordered_fieldnames = [ 'latitude', 'longitude', 'altitude' ] + format = '>iii' + native_format = bytearray('>iii', 'ascii') + orders = [0, 1, 2] + lengths = [1, 1, 1] + array_lengths = [0, 0, 0] + crc_extra = 14 + + def __init__(self, latitude, longitude, altitude): + MAVLink_message.__init__(self, MAVLink_gps_local_origin_set_message.id, MAVLink_gps_local_origin_set_message.name) + self._fieldnames = MAVLink_gps_local_origin_set_message.fieldnames + self.latitude = latitude + self.longitude = longitude + self.altitude = altitude + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude)) + +class MAVLink_local_position_setpoint_set_message(MAVLink_message): + ''' + Set the setpoint for a local position controller. This is the + position in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the onboard + position controller. As some MAVs have a degree of freedom in + yaw (e.g. all helicopters/quadrotors), the desired yaw angle + is part of the message. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET + name = 'LOCAL_POSITION_SETPOINT_SET' + fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'x', 'y', 'z', 'yaw' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 206 + + def __init__(self, target_system, target_component, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_set_message.id, MAVLink_local_position_setpoint_set_message.name) + self._fieldnames = MAVLink_local_position_setpoint_set_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw)) + +class MAVLink_local_position_setpoint_message(MAVLink_message): + ''' + Transmit the current local setpoint of the controller to other + MAVs (collision avoidance) and to the GCS. + ''' + id = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT + name = 'LOCAL_POSITION_SETPOINT' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 50 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_local_position_setpoint_message.id, MAVLink_local_position_setpoint_message.name) + self._fieldnames = MAVLink_local_position_setpoint_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_control_status_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_CONTROL_STATUS + name = 'CONTROL_STATUS' + fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw'] + ordered_fieldnames = [ 'position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw' ] + format = '>BBBBBBBB' + native_format = bytearray('>BBBBBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 157 + + def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + MAVLink_message.__init__(self, MAVLink_control_status_message.id, MAVLink_control_status_message.name) + self._fieldnames = MAVLink_control_status_message.fieldnames + self.position_fix = position_fix + self.vision_fix = vision_fix + self.gps_fix = gps_fix + self.ahrs_health = ahrs_health + self.control_att = control_att + self.control_pos_xy = control_pos_xy + self.control_pos_z = control_pos_z + self.control_pos_yaw = control_pos_yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw)) + +class MAVLink_safety_set_allowed_area_message(MAVLink_message): + ''' + Set a safety zone (volume), which is defined by two corners of + a cube. This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. Safety + areas are often enforced by national or competition + regulations. + ''' + id = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA + name = 'SAFETY_SET_ALLOWED_AREA' + fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>BBBffffff' + native_format = bytearray('>BBBffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_set_allowed_area_message.id, MAVLink_safety_set_allowed_area_message.name) + self._fieldnames = MAVLink_safety_set_allowed_area_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_safety_allowed_area_message(MAVLink_message): + ''' + Read out the safety zone the MAV currently assumes. + ''' + id = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA + name = 'SAFETY_ALLOWED_AREA' + fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] + ordered_fieldnames = [ 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z' ] + format = '>Bffffff' + native_format = bytearray('>Bffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 108 + + def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + MAVLink_message.__init__(self, MAVLink_safety_allowed_area_message.id, MAVLink_safety_allowed_area_message.name) + self._fieldnames = MAVLink_safety_allowed_area_message.fieldnames + self.frame = frame + self.p1x = p1x + self.p1y = p1y + self.p1z = p1z + self.p2x = p2x + self.p2y = p2y + self.p2z = p2z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) + +class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST + name = 'SET_ROLL_PITCH_YAW_THRUST' + fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 213 + + def __init__(self, target_system, target_component, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_thrust_message.id, MAVLink_set_roll_pitch_yaw_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message): + ''' + Set roll, pitch and yaw. + ''' + id = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST + name = 'SET_ROLL_PITCH_YAW_SPEED_THRUST' + fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>BBffff' + native_format = bytearray('>BBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 95 + + def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_set_roll_pitch_yaw_speed_thrust_message.id, MAVLink_set_roll_pitch_yaw_speed_thrust_message.name) + self._fieldnames = MAVLink_set_roll_pitch_yaw_speed_thrust_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll', 'pitch', 'yaw', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 5 + + def __init__(self, time_us, roll, pitch, yaw, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust)) + +class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active + on the system. + ''' + id = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT + name = 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT' + fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] + ordered_fieldnames = [ 'time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust' ] + format = '>Qffff' + native_format = bytearray('>Qffff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 127 + + def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + MAVLink_message.__init__(self, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.id, MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.name) + self._fieldnames = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message.fieldnames + self.time_us = time_us + self.roll_speed = roll_speed + self.pitch_speed = pitch_speed + self.yaw_speed = yaw_speed + self.thrust = thrust + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) + +class MAVLink_nav_controller_output_message(MAVLink_message): + ''' + Outputs of the APM navigation controller. The primary use of + this message is to check the response and signs of the + controller before actual flight and to assist with tuning + controller parameters + ''' + id = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT + name = 'NAV_CONTROLLER_OUTPUT' + fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error'] + ordered_fieldnames = [ 'nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error' ] + format = '>ffhhHfff' + native_format = bytearray('>ffhhHfff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 57 + + def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + MAVLink_message.__init__(self, MAVLink_nav_controller_output_message.id, MAVLink_nav_controller_output_message.name) + self._fieldnames = MAVLink_nav_controller_output_message.fieldnames + self.nav_roll = nav_roll + self.nav_pitch = nav_pitch + self.nav_bearing = nav_bearing + self.target_bearing = target_bearing + self.wp_dist = wp_dist + self.alt_error = alt_error + self.aspd_error = aspd_error + self.xtrack_error = xtrack_error + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error)) + +class MAVLink_position_target_message(MAVLink_message): + ''' + The goal position of the system. This position is the input to + any navigation or path planning algorithm and does NOT + represent the current controller setpoint. + ''' + id = MAVLINK_MSG_ID_POSITION_TARGET + name = 'POSITION_TARGET' + fieldnames = ['x', 'y', 'z', 'yaw'] + ordered_fieldnames = [ 'x', 'y', 'z', 'yaw' ] + format = '>ffff' + native_format = bytearray('>ffff', 'ascii') + orders = [0, 1, 2, 3] + lengths = [1, 1, 1, 1] + array_lengths = [0, 0, 0, 0] + crc_extra = 126 + + def __init__(self, x, y, z, yaw): + MAVLink_message.__init__(self, MAVLink_position_target_message.id, MAVLink_position_target_message.name) + self._fieldnames = MAVLink_position_target_message.fieldnames + self.x = x + self.y = y + self.z = z + self.yaw = yaw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) + +class MAVLink_state_correction_message(MAVLink_message): + ''' + Corrects the systems state by adding an error correction term + to the position and velocity, and by rotating the attitude by + a correction angle. + ''' + id = MAVLINK_MSG_ID_STATE_CORRECTION + name = 'STATE_CORRECTION' + fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr'] + ordered_fieldnames = [ 'xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr' ] + format = '>fffffffff' + native_format = bytearray('>fffffffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 130 + + def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + MAVLink_message.__init__(self, MAVLink_state_correction_message.id, MAVLink_state_correction_message.name) + self._fieldnames = MAVLink_state_correction_message.fieldnames + self.xErr = xErr + self.yErr = yErr + self.zErr = zErr + self.rollErr = rollErr + self.pitchErr = pitchErr + self.yawErr = yawErr + self.vxErr = vxErr + self.vyErr = vyErr + self.vzErr = vzErr + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr)) + +class MAVLink_set_altitude_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_SET_ALTITUDE + name = 'SET_ALTITUDE' + fieldnames = ['target', 'mode'] + ordered_fieldnames = [ 'target', 'mode' ] + format = '>BI' + native_format = bytearray('>BI', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 119 + + def __init__(self, target, mode): + MAVLink_message.__init__(self, MAVLink_set_altitude_message.id, MAVLink_set_altitude_message.name) + self._fieldnames = MAVLink_set_altitude_message.fieldnames + self.target = target + self.mode = mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode)) + +class MAVLink_request_data_stream_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_REQUEST_DATA_STREAM + name = 'REQUEST_DATA_STREAM' + fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop'] + ordered_fieldnames = [ 'target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop' ] + format = '>BBBHB' + native_format = bytearray('>BBBHB', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0] + crc_extra = 193 + + def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + MAVLink_message.__init__(self, MAVLink_request_data_stream_message.id, MAVLink_request_data_stream_message.name) + self._fieldnames = MAVLink_request_data_stream_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.req_stream_id = req_stream_id + self.req_message_rate = req_message_rate + self.start_stop = start_stop + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop)) + +class MAVLink_hil_state_message(MAVLink_message): + ''' + This packet is useful for high throughput + applications such as hardware in the loop simulations. + ''' + id = MAVLINK_MSG_ID_HIL_STATE + name = 'HIL_STATE' + fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc'] + ordered_fieldnames = [ 'usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc' ] + format = '>Qffffffiiihhhhhh' + native_format = bytearray('>Qffffffiiihhhhhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 191 + + def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + MAVLink_message.__init__(self, MAVLink_hil_state_message.id, MAVLink_hil_state_message.name) + self._fieldnames = MAVLink_hil_state_message.fieldnames + self.usec = usec + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + self.xacc = xacc + self.yacc = yacc + self.zacc = zacc + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc)) + +class MAVLink_hil_controls_message(MAVLink_message): + ''' + Hardware in the loop control outputs + ''' + id = MAVLINK_MSG_ID_HIL_CONTROLS + name = 'HIL_CONTROLS' + fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode'] + ordered_fieldnames = [ 'time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode' ] + format = '>QffffBB' + native_format = bytearray('>QffffBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0] + crc_extra = 236 + + def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + MAVLink_message.__init__(self, MAVLink_hil_controls_message.id, MAVLink_hil_controls_message.name) + self._fieldnames = MAVLink_hil_controls_message.fieldnames + self.time_us = time_us + self.roll_ailerons = roll_ailerons + self.pitch_elevator = pitch_elevator + self.yaw_rudder = yaw_rudder + self.throttle = throttle + self.mode = mode + self.nav_mode = nav_mode + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode)) + +class MAVLink_manual_control_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_MANUAL_CONTROL + name = 'MANUAL_CONTROL' + fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual'] + ordered_fieldnames = [ 'target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual' ] + format = '>BffffBBBB' + native_format = bytearray('>BffffBBBB', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 158 + + def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + MAVLink_message.__init__(self, MAVLink_manual_control_message.id, MAVLink_manual_control_message.name) + self._fieldnames = MAVLink_manual_control_message.fieldnames + self.target = target + self.roll = roll + self.pitch = pitch + self.yaw = yaw + self.thrust = thrust + self.roll_manual = roll_manual + self.pitch_manual = pitch_manual + self.yaw_manual = yaw_manual + self.thrust_manual = thrust_manual + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual)) + +class MAVLink_rc_channels_override_message(MAVLink_message): + ''' + The RAW values of the RC channels sent to the MAV to override + info received from the RC radio. A value of -1 means no change + to that channel. A value of 0 means control of that channel + should be released back to the RC radio. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters might + violate this specification. + ''' + id = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE + name = 'RC_CHANNELS_OVERRIDE' + fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw'] + ordered_fieldnames = [ 'target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw' ] + format = '>BBHHHHHHHH' + native_format = bytearray('>BBHHHHHHHH', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] + lengths = [1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 143 + + def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + MAVLink_message.__init__(self, MAVLink_rc_channels_override_message.id, MAVLink_rc_channels_override_message.name) + self._fieldnames = MAVLink_rc_channels_override_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.chan1_raw = chan1_raw + self.chan2_raw = chan2_raw + self.chan3_raw = chan3_raw + self.chan4_raw = chan4_raw + self.chan5_raw = chan5_raw + self.chan6_raw = chan6_raw + self.chan7_raw = chan7_raw + self.chan8_raw = chan8_raw + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw)) + +class MAVLink_global_position_int_message(MAVLink_message): + ''' + The filtered global position (e.g. fused GPS and + accelerometers). The position is in GPS-frame (right-handed, + Z-up) + ''' + id = MAVLINK_MSG_ID_GLOBAL_POSITION_INT + name = 'GLOBAL_POSITION_INT' + fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz'] + ordered_fieldnames = [ 'lat', 'lon', 'alt', 'vx', 'vy', 'vz' ] + format = '>iiihhh' + native_format = bytearray('>iiihhh', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 104 + + def __init__(self, lat, lon, alt, vx, vy, vz): + MAVLink_message.__init__(self, MAVLink_global_position_int_message.id, MAVLink_global_position_int_message.name) + self._fieldnames = MAVLink_global_position_int_message.fieldnames + self.lat = lat + self.lon = lon + self.alt = alt + self.vx = vx + self.vy = vy + self.vz = vz + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) + +class MAVLink_vfr_hud_message(MAVLink_message): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + ''' + id = MAVLINK_MSG_ID_VFR_HUD + name = 'VFR_HUD' + fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb'] + ordered_fieldnames = [ 'airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb' ] + format = '>ffhHff' + native_format = bytearray('>ffhHff', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 123 + + def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb): + MAVLink_message.__init__(self, MAVLink_vfr_hud_message.id, MAVLink_vfr_hud_message.name) + self._fieldnames = MAVLink_vfr_hud_message.fieldnames + self.airspeed = airspeed + self.groundspeed = groundspeed + self.heading = heading + self.throttle = throttle + self.alt = alt + self.climb = climb + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb)) + +class MAVLink_command_message(MAVLink_message): + ''' + Send a command with up to four parameters to the MAV + ''' + id = MAVLINK_MSG_ID_COMMAND + name = 'COMMAND' + fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4'] + ordered_fieldnames = [ 'target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4' ] + format = '>BBBBffff' + native_format = bytearray('>BBBBffff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6, 7] + lengths = [1, 1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0, 0, 0] + crc_extra = 131 + + def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + MAVLink_message.__init__(self, MAVLink_command_message.id, MAVLink_command_message.name) + self._fieldnames = MAVLink_command_message.fieldnames + self.target_system = target_system + self.target_component = target_component + self.command = command + self.confirmation = confirmation + self.param1 = param1 + self.param2 = param2 + self.param3 = param3 + self.param4 = param4 + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4)) + +class MAVLink_command_ack_message(MAVLink_message): + ''' + Report status of a command. Includes feedback wether the + command was executed + ''' + id = MAVLINK_MSG_ID_COMMAND_ACK + name = 'COMMAND_ACK' + fieldnames = ['command', 'result'] + ordered_fieldnames = [ 'command', 'result' ] + format = '>ff' + native_format = bytearray('>ff', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 8 + + def __init__(self, command, result): + MAVLink_message.__init__(self, MAVLink_command_ack_message.id, MAVLink_command_ack_message.name) + self._fieldnames = MAVLink_command_ack_message.fieldnames + self.command = command + self.result = result + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result)) + +class MAVLink_optical_flow_message(MAVLink_message): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + ''' + id = MAVLINK_MSG_ID_OPTICAL_FLOW + name = 'OPTICAL_FLOW' + fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance'] + ordered_fieldnames = [ 'time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance' ] + format = '>QBhhBf' + native_format = bytearray('>QBhhBf', 'ascii') + orders = [0, 1, 2, 3, 4, 5] + lengths = [1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 0, 0, 0] + crc_extra = 174 + + def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + MAVLink_message.__init__(self, MAVLink_optical_flow_message.id, MAVLink_optical_flow_message.name) + self._fieldnames = MAVLink_optical_flow_message.fieldnames + self.time = time + self.sensor_id = sensor_id + self.flow_x = flow_x + self.flow_y = flow_y + self.quality = quality + self.ground_distance = ground_distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance)) + +class MAVLink_object_detection_event_message(MAVLink_message): + ''' + Object has been detected + ''' + id = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT + name = 'OBJECT_DETECTION_EVENT' + fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance'] + ordered_fieldnames = [ 'time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance' ] + format = '>IHB20sBff' + native_format = bytearray('>IHBcBff', 'ascii') + orders = [0, 1, 2, 3, 4, 5, 6] + lengths = [1, 1, 1, 1, 1, 1, 1] + array_lengths = [0, 0, 0, 20, 0, 0, 0] + crc_extra = 155 + + def __init__(self, time, object_id, type, name, quality, bearing, distance): + MAVLink_message.__init__(self, MAVLink_object_detection_event_message.id, MAVLink_object_detection_event_message.name) + self._fieldnames = MAVLink_object_detection_event_message.fieldnames + self.time = time + self.object_id = object_id + self.type = type + self.name = name + self.quality = quality + self.bearing = bearing + self.distance = distance + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance)) + +class MAVLink_debug_vect_message(MAVLink_message): + ''' + + ''' + id = MAVLINK_MSG_ID_DEBUG_VECT + name = 'DEBUG_VECT' + fieldnames = ['name', 'usec', 'x', 'y', 'z'] + ordered_fieldnames = [ 'name', 'usec', 'x', 'y', 'z' ] + format = '>10sQfff' + native_format = bytearray('>cQfff', 'ascii') + orders = [0, 1, 2, 3, 4] + lengths = [1, 1, 1, 1, 1] + array_lengths = [10, 0, 0, 0, 0] + crc_extra = 178 + + def __init__(self, name, usec, x, y, z): + MAVLink_message.__init__(self, MAVLink_debug_vect_message.id, MAVLink_debug_vect_message.name) + self._fieldnames = MAVLink_debug_vect_message.fieldnames + self.name = name + self.usec = usec + self.x = x + self.y = y + self.z = z + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z)) + +class MAVLink_named_value_float_message(MAVLink_message): + ''' + Send a key-value pair as float. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT + name = 'NAMED_VALUE_FLOAT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10sf' + native_format = bytearray('>cf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 224 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_float_message.id, MAVLink_named_value_float_message.name) + self._fieldnames = MAVLink_named_value_float_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value)) + +class MAVLink_named_value_int_message(MAVLink_message): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient way for + testing new messages and getting experimental debug output. + ''' + id = MAVLINK_MSG_ID_NAMED_VALUE_INT + name = 'NAMED_VALUE_INT' + fieldnames = ['name', 'value'] + ordered_fieldnames = [ 'name', 'value' ] + format = '>10si' + native_format = bytearray('>ci', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [10, 0] + crc_extra = 60 + + def __init__(self, name, value): + MAVLink_message.__init__(self, MAVLink_named_value_int_message.id, MAVLink_named_value_int_message.name) + self._fieldnames = MAVLink_named_value_int_message.fieldnames + self.name = name + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value)) + +class MAVLink_statustext_message(MAVLink_message): + ''' + Status text message. These messages are printed in yellow in + the COMM console of QGroundControl. WARNING: They consume + quite some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages are + buffered on the MCU and sent only at a limited rate (e.g. 10 + Hz). + ''' + id = MAVLINK_MSG_ID_STATUSTEXT + name = 'STATUSTEXT' + fieldnames = ['severity', 'text'] + ordered_fieldnames = [ 'severity', 'text' ] + format = '>B50b' + native_format = bytearray('>Bb', 'ascii') + orders = [0, 1] + lengths = [1, 50] + array_lengths = [0, 50] + crc_extra = 106 + + def __init__(self, severity, text): + MAVLink_message.__init__(self, MAVLink_statustext_message.id, MAVLink_statustext_message.name) + self._fieldnames = MAVLink_statustext_message.fieldnames + self.severity = severity + self.text = text + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 106, struct.pack('>B50b', self.severity, self.text[0], self.text[1], self.text[2], self.text[3], self.text[4], self.text[5], self.text[6], self.text[7], self.text[8], self.text[9], self.text[10], self.text[11], self.text[12], self.text[13], self.text[14], self.text[15], self.text[16], self.text[17], self.text[18], self.text[19], self.text[20], self.text[21], self.text[22], self.text[23], self.text[24], self.text[25], self.text[26], self.text[27], self.text[28], self.text[29], self.text[30], self.text[31], self.text[32], self.text[33], self.text[34], self.text[35], self.text[36], self.text[37], self.text[38], self.text[39], self.text[40], self.text[41], self.text[42], self.text[43], self.text[44], self.text[45], self.text[46], self.text[47], self.text[48], self.text[49])) + +class MAVLink_debug_message(MAVLink_message): + ''' + Send a debug value. The index is used to discriminate between + values. These values show up in the plot of QGroundControl as + DEBUG N. + ''' + id = MAVLINK_MSG_ID_DEBUG + name = 'DEBUG' + fieldnames = ['ind', 'value'] + ordered_fieldnames = [ 'ind', 'value' ] + format = '>Bf' + native_format = bytearray('>Bf', 'ascii') + orders = [0, 1] + lengths = [1, 1] + array_lengths = [0, 0] + crc_extra = 7 + + def __init__(self, ind, value): + MAVLink_message.__init__(self, MAVLink_debug_message.id, MAVLink_debug_message.name) + self._fieldnames = MAVLink_debug_message.fieldnames + self.ind = ind + self.value = value + + def pack(self, mav): + return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value)) + + +mavlink_map = { + MAVLINK_MSG_ID_NAV_FILTER_BIAS : MAVLink_nav_filter_bias_message, + MAVLINK_MSG_ID_RADIO_CALIBRATION : MAVLink_radio_calibration_message, + MAVLINK_MSG_ID_UALBERTA_SYS_STATUS : MAVLink_ualberta_sys_status_message, + MAVLINK_MSG_ID_HEARTBEAT : MAVLink_heartbeat_message, + MAVLINK_MSG_ID_BOOT : MAVLink_boot_message, + MAVLINK_MSG_ID_SYSTEM_TIME : MAVLink_system_time_message, + MAVLINK_MSG_ID_PING : MAVLink_ping_message, + MAVLINK_MSG_ID_SYSTEM_TIME_UTC : MAVLink_system_time_utc_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : MAVLink_change_operator_control_message, + MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : MAVLink_change_operator_control_ack_message, + MAVLINK_MSG_ID_AUTH_KEY : MAVLink_auth_key_message, + MAVLINK_MSG_ID_ACTION_ACK : MAVLink_action_ack_message, + MAVLINK_MSG_ID_ACTION : MAVLink_action_message, + MAVLINK_MSG_ID_SET_MODE : MAVLink_set_mode_message, + MAVLINK_MSG_ID_SET_NAV_MODE : MAVLink_set_nav_mode_message, + MAVLINK_MSG_ID_PARAM_REQUEST_READ : MAVLink_param_request_read_message, + MAVLINK_MSG_ID_PARAM_REQUEST_LIST : MAVLink_param_request_list_message, + MAVLINK_MSG_ID_PARAM_VALUE : MAVLink_param_value_message, + MAVLINK_MSG_ID_PARAM_SET : MAVLink_param_set_message, + MAVLINK_MSG_ID_GPS_RAW_INT : MAVLink_gps_raw_int_message, + MAVLINK_MSG_ID_SCALED_IMU : MAVLink_scaled_imu_message, + MAVLINK_MSG_ID_GPS_STATUS : MAVLink_gps_status_message, + MAVLINK_MSG_ID_RAW_IMU : MAVLink_raw_imu_message, + MAVLINK_MSG_ID_RAW_PRESSURE : MAVLink_raw_pressure_message, + MAVLINK_MSG_ID_SCALED_PRESSURE : MAVLink_scaled_pressure_message, + MAVLINK_MSG_ID_ATTITUDE : MAVLink_attitude_message, + MAVLINK_MSG_ID_LOCAL_POSITION : MAVLink_local_position_message, + MAVLINK_MSG_ID_GLOBAL_POSITION : MAVLink_global_position_message, + MAVLINK_MSG_ID_GPS_RAW : MAVLink_gps_raw_message, + MAVLINK_MSG_ID_SYS_STATUS : MAVLink_sys_status_message, + MAVLINK_MSG_ID_RC_CHANNELS_RAW : MAVLink_rc_channels_raw_message, + MAVLINK_MSG_ID_RC_CHANNELS_SCALED : MAVLink_rc_channels_scaled_message, + MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : MAVLink_servo_output_raw_message, + MAVLINK_MSG_ID_WAYPOINT : MAVLink_waypoint_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST : MAVLink_waypoint_request_message, + MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : MAVLink_waypoint_set_current_message, + MAVLINK_MSG_ID_WAYPOINT_CURRENT : MAVLink_waypoint_current_message, + MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : MAVLink_waypoint_request_list_message, + MAVLINK_MSG_ID_WAYPOINT_COUNT : MAVLink_waypoint_count_message, + MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : MAVLink_waypoint_clear_all_message, + MAVLINK_MSG_ID_WAYPOINT_REACHED : MAVLink_waypoint_reached_message, + MAVLINK_MSG_ID_WAYPOINT_ACK : MAVLink_waypoint_ack_message, + MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : MAVLink_gps_set_global_origin_message, + MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : MAVLink_gps_local_origin_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : MAVLink_local_position_setpoint_set_message, + MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : MAVLink_local_position_setpoint_message, + MAVLINK_MSG_ID_CONTROL_STATUS : MAVLink_control_status_message, + MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : MAVLink_safety_set_allowed_area_message, + MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : MAVLink_safety_allowed_area_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : MAVLink_set_roll_pitch_yaw_thrust_message, + MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : MAVLink_set_roll_pitch_yaw_speed_thrust_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_thrust_setpoint_message, + MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, + MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : MAVLink_nav_controller_output_message, + MAVLINK_MSG_ID_POSITION_TARGET : MAVLink_position_target_message, + MAVLINK_MSG_ID_STATE_CORRECTION : MAVLink_state_correction_message, + MAVLINK_MSG_ID_SET_ALTITUDE : MAVLink_set_altitude_message, + MAVLINK_MSG_ID_REQUEST_DATA_STREAM : MAVLink_request_data_stream_message, + MAVLINK_MSG_ID_HIL_STATE : MAVLink_hil_state_message, + MAVLINK_MSG_ID_HIL_CONTROLS : MAVLink_hil_controls_message, + MAVLINK_MSG_ID_MANUAL_CONTROL : MAVLink_manual_control_message, + MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : MAVLink_rc_channels_override_message, + MAVLINK_MSG_ID_GLOBAL_POSITION_INT : MAVLink_global_position_int_message, + MAVLINK_MSG_ID_VFR_HUD : MAVLink_vfr_hud_message, + MAVLINK_MSG_ID_COMMAND : MAVLink_command_message, + MAVLINK_MSG_ID_COMMAND_ACK : MAVLink_command_ack_message, + MAVLINK_MSG_ID_OPTICAL_FLOW : MAVLink_optical_flow_message, + MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : MAVLink_object_detection_event_message, + MAVLINK_MSG_ID_DEBUG_VECT : MAVLink_debug_vect_message, + MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : MAVLink_named_value_float_message, + MAVLINK_MSG_ID_NAMED_VALUE_INT : MAVLink_named_value_int_message, + MAVLINK_MSG_ID_STATUSTEXT : MAVLink_statustext_message, + MAVLINK_MSG_ID_DEBUG : MAVLink_debug_message, +} + +class MAVError(Exception): + '''MAVLink error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = msg + +class MAVString(str): + '''NUL terminated string''' + def __init__(self, s): + str.__init__(self) + def __str__(self): + i = self.find(chr(0)) + if i == -1: + return self[:] + return self[0:i] + +class MAVLink_bad_data(MAVLink_message): + ''' + a piece of bad data in a mavlink stream + ''' + def __init__(self, data, reason): + MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') + self._fieldnames = ['data', 'reason'] + self.data = data + self.reason = reason + self._msgbuf = data + + def __str__(self): + '''Override the __str__ function from MAVLink_messages because non-printable characters are common in to be the reason for this message to exist.''' + return '%s {%s, data:%s}' % (self._type, self.reason, [('%x' % ord(i) if isinstance(i, str) else '%x' % i) for i in self.data]) + +class MAVLink(object): + '''MAVLink protocol handling class''' + def __init__(self, file, srcSystem=0, srcComponent=0, use_native=False): + self.seq = 0 + self.file = file + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.callback = None + self.callback_args = None + self.callback_kwargs = None + self.send_callback = None + self.send_callback_args = None + self.send_callback_kwargs = None + self.buf = bytearray() + self.expected_length = 8 + self.have_prefix_error = False + self.robust_parsing = False + self.protocol_marker = 85 + self.little_endian = False + self.crc_extra = False + self.sort_fields = False + self.total_packets_sent = 0 + self.total_bytes_sent = 0 + self.total_packets_received = 0 + self.total_bytes_received = 0 + self.total_receive_errors = 0 + self.startup_time = time.time() + if native_supported and (use_native or native_testing or native_force): + print("NOTE: mavnative is currently beta-test code") + self.native = mavnative.NativeConnection(MAVLink_message, mavlink_map) + else: + self.native = None + if native_testing: + self.test_buf = bytearray() + + def set_callback(self, callback, *args, **kwargs): + self.callback = callback + self.callback_args = args + self.callback_kwargs = kwargs + + def set_send_callback(self, callback, *args, **kwargs): + self.send_callback = callback + self.send_callback_args = args + self.send_callback_kwargs = kwargs + + def send(self, mavmsg): + '''send a MAVLink message''' + buf = mavmsg.pack(self) + self.file.write(buf) + self.seq = (self.seq + 1) % 256 + self.total_packets_sent += 1 + self.total_bytes_sent += len(buf) + if self.send_callback: + self.send_callback(mavmsg, *self.send_callback_args, **self.send_callback_kwargs) + + def bytes_needed(self): + '''return number of bytes needed for next parsing stage''' + if self.native: + ret = self.native.expected_length - len(self.buf) + else: + ret = self.expected_length - len(self.buf) + + if ret <= 0: + return 1 + return ret + + def __parse_char_native(self, c): + '''this method exists only to see in profiling results''' + m = self.native.parse_chars(c) + return m + + def __callbacks(self, msg): + '''this method exists only to make profiling results easier to read''' + if self.callback: + self.callback(msg, *self.callback_args, **self.callback_kwargs) + + def parse_char(self, c): + '''input some data bytes, possibly returning a new message''' + self.buf.extend(c) + + self.total_bytes_received += len(c) + + if self.native: + if native_testing: + self.test_buf.extend(c) + m = self.__parse_char_native(self.test_buf) + m2 = self.__parse_char_legacy() + if m2 != m: + print("Native: %s\nLegacy: %s\n" % (m, m2)) + raise Exception('Native vs. Legacy mismatch') + else: + m = self.__parse_char_native(self.buf) + else: + m = self.__parse_char_legacy() + + if m != None: + self.total_packets_received += 1 + self.__callbacks(m) + + return m + + def __parse_char_legacy(self): + '''input some data bytes, possibly returning a new message (uses no native code)''' + if len(self.buf) >= 1 and self.buf[0] != 85: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 85: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value) + + def param_set_send(self, target_system, target_component, param_id, param_value): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id (int8_t) + param_value : Onboard parameter value (float) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value)) + + def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in 1E7 degrees (int32_t) + lon : Longitude in 1E7 degrees (int32_t) + alt : Altitude in 1E3 meters (millimeters) (int32_t) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (m/s) (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (int8_t) + satellite_used : 0: Satellite not used, 1: used for localization (int8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) + satellite_snr : Signal to noise ratio of satellite (int8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw) (int16_t) + press_diff2 : Differential pressure 2 (raw) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, usec, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature)) + + def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def local_position_encode(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_message(usec, x, y, z, vx, vy, vz) + + def local_position_send(self, usec, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz)) + + def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz) + + def global_position_send(self, usec, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since unix epoch) (uint64_t) + lat : Latitude, in degrees (float) + lon : Longitude, in degrees (float) + alt : Absolute altitude, in meters (float) + vx : X Speed (in Latitude direction, positive: going north) (float) + vy : Y Speed (in Longitude direction, positive: going east) (float) + vz : Z Speed (in Altitude direction, positive: going up) (float) + + ''' + return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz)) + + def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) + + def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position estimate of the + sytem, but rather a RAW sensor value. See message + GLOBAL_POSITION for the global position estimate. + Coordinate frame is right-handed, Z-axis up (GPS + frame) + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + eph : GPS HDOP (float) + epv : GPS VDOP (float) + v : GPS ground speed (float) + hdg : Compass heading in degrees, 0..360 degrees (float) + + ''' + return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) + + def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop) + + def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) + nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) + status : System status flag, see MAV_STATUS ENUM (uint8_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) + packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) + + ''' + return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)) + + def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000 + + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on + the system. The waypoint can be either in x, y, z + meters (type: LOCAL) or x:lat, y:lon, z:altitude. + Local frame is Z-down, right handed, global frame is + Z-up, right handed + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) + param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) + param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) + param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (float) + + ''' + return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def waypoint_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_request_message(target_system, target_component, seq) + + def waypoint_request_send(self, target_system, target_component, seq): + ''' + Request the information of the waypoint with the sequence number seq. + The response of the system to this message should be a + WAYPOINT message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_request_encode(target_system, target_component, seq)) + + def waypoint_set_current_encode(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_set_current_message(target_system, target_component, seq) + + def waypoint_set_current_send(self, target_system, target_component, seq): + ''' + Set the waypoint with sequence number seq as current waypoint. This + means that the MAV will continue to this waypoint on + the shortest path (not following the waypoints in- + between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_set_current_encode(target_system, target_component, seq)) + + def waypoint_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_current_message(seq) + + def waypoint_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + waypoint. The MAV will fly towards this waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_current_encode(seq)) + + def waypoint_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_request_list_message(target_system, target_component) + + def waypoint_request_list_send(self, target_system, target_component): + ''' + Request the overall list of waypoints from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_request_list_encode(target_system, target_component)) + + def waypoint_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return MAVLink_waypoint_count_message(target_system, target_component, count) + + def waypoint_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to WAYPOINT_REQUEST_LIST by the + MAV. The GCS can then request the individual waypoints + based on the knowledge of the total number of + waypoints. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of Waypoints in the Sequence (uint16_t) + + ''' + return self.send(self.waypoint_count_encode(target_system, target_component, count)) + + def waypoint_clear_all_encode(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_waypoint_clear_all_message(target_system, target_component) + + def waypoint_clear_all_send(self, target_system, target_component): + ''' + Delete all waypoints at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.waypoint_clear_all_encode(target_system, target_component)) + + def waypoint_reached_encode(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_waypoint_reached_message(seq) + + def waypoint_reached_send(self, seq): + ''' + A certain waypoint has been reached. The system will either hold this + position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + waypoint. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.waypoint_reached_encode(seq)) + + def waypoint_ack_encode(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return MAVLink_waypoint_ack_message(target_system, target_component, type) + + def waypoint_ack_send(self, target_system, target_component, type): + ''' + Ack message during waypoint handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : 0: OK, 1: Error (uint8_t) + + ''' + return self.send(self.waypoint_ack_encode(target_system, target_component, type)) + + def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude) + + def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude): + ''' + As local waypoints exist, the global waypoint reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + latitude : global position * 1E7 (int32_t) + longitude : global position * 1E7 (int32_t) + altitude : global position * 1000 (int32_t) + + ''' + return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude)) + + def gps_local_origin_set_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return MAVLink_gps_local_origin_set_message(latitude, longitude, altitude) + + def gps_local_origin_set_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) + longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) + altitude : Altitude(WGS84), expressed as * 1000 (int32_t) + + ''' + return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude)) + + def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw) + + def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw): + ''' + Set the setpoint for a local position controller. This is the position + in local coordinates the MAV should fly to. This + message is sent by the path/waypoint planner to the + onboard position controller. As some MAVs have a + degree of freedom in yaw (e.g. all + helicopters/quadrotors), the desired yaw angle is part + of the message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw)) + + def local_position_setpoint_encode(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return MAVLink_local_position_setpoint_message(x, y, z, yaw) + + def local_position_setpoint_send(self, x, y, z, yaw): + ''' + Transmit the current local setpoint of the controller to other MAVs + (collision avoidance) and to the GCS. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : Desired yaw angle (float) + + ''' + return self.send(self.local_position_setpoint_encode(x, y, z, yaw)) + + def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw) + + def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): + ''' + + + position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) + vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) + gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) + ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) + control_att : 0: Attitude control disabled, 1: enabled (uint8_t) + control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) + control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) + control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) + + ''' + return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/waypoints to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) + + def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) + + def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) + + def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Set roll, pitch and yaw. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) + + def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust) + + def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust): + ''' + Setpoint in roll, pitch, yaw currently active on the system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll : Desired roll angle in radians (float) + pitch : Desired pitch angle in radians (float) + yaw : Desired yaw angle in radians (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust)) + + def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust) + + def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): + ''' + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the + system. + + time_us : Timestamp in micro seconds since unix epoch (uint64_t) + roll_speed : Desired roll angular speed in rad/s (float) + pitch_speed : Desired pitch angular speed in rad/s (float) + yaw_speed : Desired yaw angular speed in rad/s (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + + ''' + return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current waypoint/target in degrees (int16_t) + wp_dist : Distance to active waypoint in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def position_target_encode(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return MAVLink_position_target_message(x, y, z, yaw) + + def position_target_send(self, x, y, z, yaw): + ''' + The goal position of the system. This position is the input to any + navigation or path planning algorithm and does NOT + represent the current controller setpoint. + + x : x position (float) + y : y position (float) + z : z position (float) + yaw : yaw orientation in radians, 0 = NORTH (float) + + ''' + return self.send(self.position_target_encode(x, y, z, yaw)) + + def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) + + def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): + ''' + Corrects the systems state by adding an error correction term to the + position and velocity, and by rotating the attitude by + a correction angle. + + xErr : x position error (float) + yErr : y position error (float) + zErr : z position error (float) + rollErr : roll error (radians) (float) + pitchErr : pitch error (radians) (float) + yawErr : yaw error (radians) (float) + vxErr : x velocity (float) + vyErr : y velocity (float) + vzErr : z velocity (float) + + ''' + return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) + + def set_altitude_encode(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return MAVLink_set_altitude_message(target, mode) + + def set_altitude_send(self, target, mode): + ''' + + + target : The system setting the altitude (uint8_t) + mode : The new altitude in meters (uint32_t) + + ''' + return self.send(self.set_altitude_encode(target, mode)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested message type (uint8_t) + req_message_rate : Update rate in Hertz (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + This packet is useful for high throughput applications + such as hardware in the loop simulations. + + usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode) + + def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): + ''' + Hardware in the loop control outputs + + time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -3 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)) + + def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) + + def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): + ''' + + + target : The system to be controlled (uint8_t) + roll : roll (float) + pitch : pitch (float) + yaw : yaw (float) + thrust : thrust (float) + roll_manual : roll control enabled auto:0, manual:1 (uint8_t) + pitch_manual : pitch auto:0, manual:1 (uint8_t) + yaw_manual : yaw auto:0, manual:1 (uint8_t) + thrust_manual : thrust auto:0, manual:1 (uint8_t) + + ''' + return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of -1 means no + change to that channel. A value of 0 means control of + that channel should be released back to the RC radio. + The standard PPM modulation is as follows: 1000 + microseconds: 0%, 2000 microseconds: 100%. Individual + receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def global_position_int_encode(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz) + + def global_position_int_send(self, lat, lon, alt, vx, vy, vz): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up) + + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + + ''' + return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4) + + def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): + ''' + Send a command with up to four parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint8_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed + + command : Current airspeed in m/s (float) + result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance) + + def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels in x-sensor direction (int16_t) + flow_y : Flow in pixels in y-sensor direction (int16_t) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters (float) + + ''' + return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance)) + + def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance) + + def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance): + ''' + Object has been detected + + time : Timestamp in milliseconds since system boot (uint32_t) + object_id : Object ID (uint16_t) + type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) + name : Name of the object as defined by the detector (char) + quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) + bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) + distance : Ground distance in meters (float) + + ''' + return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance)) + + def debug_vect_encode(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, usec, x, y, z) + + def debug_vect_send(self, name, usec, x, y, z): + ''' + + + name : Name (char) + usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, usec, x, y, z)) + + def named_value_float_encode(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(name, value) + + def named_value_float_send(self, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(name, value)) + + def named_value_int_encode(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(name, value) + + def named_value_int_send(self, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) + text : Status text message, without null termination character (int8_t) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(ind, value) + + def debug_send(self, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(ind, value)) + diff --git a/pymavlink/dialects/v09/ualberta.xml b/pymavlink/dialects/v09/ualberta.xml new file mode 100644 index 0000000..4023aa9 --- /dev/null +++ b/pymavlink/dialects/v09/ualberta.xml @@ -0,0 +1,54 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + Raw input pulse widts sent to output + Inputs are normalized using calibration, the converted back to raw pulse widths for output + dfsdfs + dfsfds + dfsdfsdfs + + + Navigation filter mode + + AHRS mode + INS/GPS initialization mode + INS/GPS mode + + + Mode currently commanded by pilot + sdf + dfs + Rotomotion mode + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/pymavlink/dialects/v10/ASLUAV.py b/pymavlink/dialects/v10/ASLUAV.py new file mode 100644 index 0000000..ea9dd85 --- /dev/null +++ b/pymavlink/dialects/v10/ASLUAV.py @@ -0,0 +1,11730 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: ASLUAV.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "ASLUAV" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_RESET_MPPT = 40001 # Mission command to reset Maximum Power Point Tracker (MPPT) +enums['MAV_CMD'][40001] = EnumEntry('MAV_CMD_RESET_MPPT', '''Mission command to reset Maximum Power Point Tracker (MPPT)''') +enums['MAV_CMD'][40001].param[1] = '''MPPT number''' +enums['MAV_CMD'][40001].param[2] = '''Empty''' +enums['MAV_CMD'][40001].param[3] = '''Empty''' +enums['MAV_CMD'][40001].param[4] = '''Empty''' +enums['MAV_CMD'][40001].param[5] = '''Empty''' +enums['MAV_CMD'][40001].param[6] = '''Empty''' +enums['MAV_CMD'][40001].param[7] = '''Empty''' +MAV_CMD_PAYLOAD_CONTROL = 40002 # Mission command to perform a power cycle on payload +enums['MAV_CMD'][40002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL', '''Mission command to perform a power cycle on payload''') +enums['MAV_CMD'][40002].param[1] = '''Complete power cycle''' +enums['MAV_CMD'][40002].param[2] = '''VISensor power cycle''' +enums['MAV_CMD'][40002].param[3] = '''Empty''' +enums['MAV_CMD'][40002].param[4] = '''Empty''' +enums['MAV_CMD'][40002].param[5] = '''Empty''' +enums['MAV_CMD'][40002].param[6] = '''Empty''' +enums['MAV_CMD'][40002].param[7] = '''Empty''' +MAV_CMD_ENUM_END = 40003 # +enums['MAV_CMD'][40003] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_AUTOPILOT +enums['MAV_AUTOPILOT'] = {} +MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything +enums['MAV_AUTOPILOT'][0] = EnumEntry('MAV_AUTOPILOT_GENERIC', '''Generic autopilot, full support for everything''') +MAV_AUTOPILOT_RESERVED = 1 # Reserved for future use. +enums['MAV_AUTOPILOT'][1] = EnumEntry('MAV_AUTOPILOT_RESERVED', '''Reserved for future use.''') +MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu +enums['MAV_AUTOPILOT'][2] = EnumEntry('MAV_AUTOPILOT_SLUGS', '''SLUGS autopilot, http://slugsuav.soe.ucsc.edu''') +MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com +enums['MAV_AUTOPILOT'][3] = EnumEntry('MAV_AUTOPILOT_ARDUPILOTMEGA', '''ArduPilotMega / ArduCopter, http://diydrones.com''') +MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org +enums['MAV_AUTOPILOT'][4] = EnumEntry('MAV_AUTOPILOT_OPENPILOT', '''OpenPilot, http://openpilot.org''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints +enums['MAV_AUTOPILOT'][5] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY', '''Generic autopilot only supporting simple waypoints''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation + # commands +enums['MAV_AUTOPILOT'][6] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY', '''Generic autopilot supporting waypoints and other simple navigation commands''') +MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set +enums['MAV_AUTOPILOT'][7] = EnumEntry('MAV_AUTOPILOT_GENERIC_MISSION_FULL', '''Generic autopilot supporting the full mission command set''') +MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component +enums['MAV_AUTOPILOT'][8] = EnumEntry('MAV_AUTOPILOT_INVALID', '''No valid autopilot, e.g. a GCS or other MAVLink component''') +MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi +enums['MAV_AUTOPILOT'][9] = EnumEntry('MAV_AUTOPILOT_PPZ', '''PPZ UAV - http://nongnu.org/paparazzi''') +MAV_AUTOPILOT_UDB = 10 # UAV Dev Board +enums['MAV_AUTOPILOT'][10] = EnumEntry('MAV_AUTOPILOT_UDB', '''UAV Dev Board''') +MAV_AUTOPILOT_FP = 11 # FlexiPilot +enums['MAV_AUTOPILOT'][11] = EnumEntry('MAV_AUTOPILOT_FP', '''FlexiPilot''') +MAV_AUTOPILOT_PX4 = 12 # PX4 Autopilot - http://pixhawk.ethz.ch/px4/ +enums['MAV_AUTOPILOT'][12] = EnumEntry('MAV_AUTOPILOT_PX4', '''PX4 Autopilot - http://pixhawk.ethz.ch/px4/''') +MAV_AUTOPILOT_SMACCMPILOT = 13 # SMACCMPilot - http://smaccmpilot.org +enums['MAV_AUTOPILOT'][13] = EnumEntry('MAV_AUTOPILOT_SMACCMPILOT', '''SMACCMPilot - http://smaccmpilot.org''') +MAV_AUTOPILOT_AUTOQUAD = 14 # AutoQuad -- http://autoquad.org +enums['MAV_AUTOPILOT'][14] = EnumEntry('MAV_AUTOPILOT_AUTOQUAD', '''AutoQuad -- http://autoquad.org''') +MAV_AUTOPILOT_ARMAZILA = 15 # Armazila -- http://armazila.com +enums['MAV_AUTOPILOT'][15] = EnumEntry('MAV_AUTOPILOT_ARMAZILA', '''Armazila -- http://armazila.com''') +MAV_AUTOPILOT_AEROB = 16 # Aerob -- http://aerob.ru +enums['MAV_AUTOPILOT'][16] = EnumEntry('MAV_AUTOPILOT_AEROB', '''Aerob -- http://aerob.ru''') +MAV_AUTOPILOT_ASLUAV = 17 # ASLUAV autopilot -- http://www.asl.ethz.ch +enums['MAV_AUTOPILOT'][17] = EnumEntry('MAV_AUTOPILOT_ASLUAV', '''ASLUAV autopilot -- http://www.asl.ethz.ch''') +MAV_AUTOPILOT_ENUM_END = 18 # +enums['MAV_AUTOPILOT'][18] = EnumEntry('MAV_AUTOPILOT_ENUM_END', '''''') + +# MAV_TYPE +enums['MAV_TYPE'] = {} +MAV_TYPE_GENERIC = 0 # Generic micro air vehicle. +enums['MAV_TYPE'][0] = EnumEntry('MAV_TYPE_GENERIC', '''Generic micro air vehicle.''') +MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft. +enums['MAV_TYPE'][1] = EnumEntry('MAV_TYPE_FIXED_WING', '''Fixed wing aircraft.''') +MAV_TYPE_QUADROTOR = 2 # Quadrotor +enums['MAV_TYPE'][2] = EnumEntry('MAV_TYPE_QUADROTOR', '''Quadrotor''') +MAV_TYPE_COAXIAL = 3 # Coaxial helicopter +enums['MAV_TYPE'][3] = EnumEntry('MAV_TYPE_COAXIAL', '''Coaxial helicopter''') +MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor. +enums['MAV_TYPE'][4] = EnumEntry('MAV_TYPE_HELICOPTER', '''Normal helicopter with tail rotor.''') +MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation +enums['MAV_TYPE'][5] = EnumEntry('MAV_TYPE_ANTENNA_TRACKER', '''Ground installation''') +MAV_TYPE_GCS = 6 # Operator control unit / ground control station +enums['MAV_TYPE'][6] = EnumEntry('MAV_TYPE_GCS', '''Operator control unit / ground control station''') +MAV_TYPE_AIRSHIP = 7 # Airship, controlled +enums['MAV_TYPE'][7] = EnumEntry('MAV_TYPE_AIRSHIP', '''Airship, controlled''') +MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled +enums['MAV_TYPE'][8] = EnumEntry('MAV_TYPE_FREE_BALLOON', '''Free balloon, uncontrolled''') +MAV_TYPE_ROCKET = 9 # Rocket +enums['MAV_TYPE'][9] = EnumEntry('MAV_TYPE_ROCKET', '''Rocket''') +MAV_TYPE_GROUND_ROVER = 10 # Ground rover +enums['MAV_TYPE'][10] = EnumEntry('MAV_TYPE_GROUND_ROVER', '''Ground rover''') +MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship +enums['MAV_TYPE'][11] = EnumEntry('MAV_TYPE_SURFACE_BOAT', '''Surface vessel, boat, ship''') +MAV_TYPE_SUBMARINE = 12 # Submarine +enums['MAV_TYPE'][12] = EnumEntry('MAV_TYPE_SUBMARINE', '''Submarine''') +MAV_TYPE_HEXAROTOR = 13 # Hexarotor +enums['MAV_TYPE'][13] = EnumEntry('MAV_TYPE_HEXAROTOR', '''Hexarotor''') +MAV_TYPE_OCTOROTOR = 14 # Octorotor +enums['MAV_TYPE'][14] = EnumEntry('MAV_TYPE_OCTOROTOR', '''Octorotor''') +MAV_TYPE_TRICOPTER = 15 # Octorotor +enums['MAV_TYPE'][15] = EnumEntry('MAV_TYPE_TRICOPTER', '''Octorotor''') +MAV_TYPE_FLAPPING_WING = 16 # Flapping wing +enums['MAV_TYPE'][16] = EnumEntry('MAV_TYPE_FLAPPING_WING', '''Flapping wing''') +MAV_TYPE_KITE = 17 # Flapping wing +enums['MAV_TYPE'][17] = EnumEntry('MAV_TYPE_KITE', '''Flapping wing''') +MAV_TYPE_ONBOARD_CONTROLLER = 18 # Onboard companion controller +enums['MAV_TYPE'][18] = EnumEntry('MAV_TYPE_ONBOARD_CONTROLLER', '''Onboard companion controller''') +MAV_TYPE_VTOL_DUOROTOR = 19 # Two-rotor VTOL using control surfaces in vertical operation in + # addition. Tailsitter. +enums['MAV_TYPE'][19] = EnumEntry('MAV_TYPE_VTOL_DUOROTOR', '''Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.''') +MAV_TYPE_VTOL_QUADROTOR = 20 # Quad-rotor VTOL using a V-shaped quad config in vertical operation. + # Tailsitter. +enums['MAV_TYPE'][20] = EnumEntry('MAV_TYPE_VTOL_QUADROTOR', '''Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.''') +MAV_TYPE_VTOL_TILTROTOR = 21 # Tiltrotor VTOL +enums['MAV_TYPE'][21] = EnumEntry('MAV_TYPE_VTOL_TILTROTOR', '''Tiltrotor VTOL''') +MAV_TYPE_VTOL_RESERVED2 = 22 # VTOL reserved 2 +enums['MAV_TYPE'][22] = EnumEntry('MAV_TYPE_VTOL_RESERVED2', '''VTOL reserved 2''') +MAV_TYPE_VTOL_RESERVED3 = 23 # VTOL reserved 3 +enums['MAV_TYPE'][23] = EnumEntry('MAV_TYPE_VTOL_RESERVED3', '''VTOL reserved 3''') +MAV_TYPE_VTOL_RESERVED4 = 24 # VTOL reserved 4 +enums['MAV_TYPE'][24] = EnumEntry('MAV_TYPE_VTOL_RESERVED4', '''VTOL reserved 4''') +MAV_TYPE_VTOL_RESERVED5 = 25 # VTOL reserved 5 +enums['MAV_TYPE'][25] = EnumEntry('MAV_TYPE_VTOL_RESERVED5', '''VTOL reserved 5''') +MAV_TYPE_GIMBAL = 26 # Onboard gimbal +enums['MAV_TYPE'][26] = EnumEntry('MAV_TYPE_GIMBAL', '''Onboard gimbal''') +MAV_TYPE_ADSB = 27 # Onboard ADSB peripheral +enums['MAV_TYPE'][27] = EnumEntry('MAV_TYPE_ADSB', '''Onboard ADSB peripheral''') +MAV_TYPE_ENUM_END = 28 # +enums['MAV_TYPE'][28] = EnumEntry('MAV_TYPE_ENUM_END', '''''') + +# FIRMWARE_VERSION_TYPE +enums['FIRMWARE_VERSION_TYPE'] = {} +FIRMWARE_VERSION_TYPE_DEV = 0 # development release +enums['FIRMWARE_VERSION_TYPE'][0] = EnumEntry('FIRMWARE_VERSION_TYPE_DEV', '''development release''') +FIRMWARE_VERSION_TYPE_ALPHA = 64 # alpha release +enums['FIRMWARE_VERSION_TYPE'][64] = EnumEntry('FIRMWARE_VERSION_TYPE_ALPHA', '''alpha release''') +FIRMWARE_VERSION_TYPE_BETA = 128 # beta release +enums['FIRMWARE_VERSION_TYPE'][128] = EnumEntry('FIRMWARE_VERSION_TYPE_BETA', '''beta release''') +FIRMWARE_VERSION_TYPE_RC = 192 # release candidate +enums['FIRMWARE_VERSION_TYPE'][192] = EnumEntry('FIRMWARE_VERSION_TYPE_RC', '''release candidate''') +FIRMWARE_VERSION_TYPE_OFFICIAL = 255 # official stable release +enums['FIRMWARE_VERSION_TYPE'][255] = EnumEntry('FIRMWARE_VERSION_TYPE_OFFICIAL', '''official stable release''') +FIRMWARE_VERSION_TYPE_ENUM_END = 256 # +enums['FIRMWARE_VERSION_TYPE'][256] = EnumEntry('FIRMWARE_VERSION_TYPE_ENUM_END', '''''') + +# MAV_MODE_FLAG +enums['MAV_MODE_FLAG'] = {} +MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use. +enums['MAV_MODE_FLAG'][1] = EnumEntry('MAV_MODE_FLAG_CUSTOM_MODE_ENABLED', '''0b00000001 Reserved for future use.''') +MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for + # temporary system tests and should not be + # used for stable implementations. +enums['MAV_MODE_FLAG'][2] = EnumEntry('MAV_MODE_FLAG_TEST_ENABLED', '''0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.''') +MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal + # positions. Guided flag can be set or not, + # depends on the actual implementation. +enums['MAV_MODE_FLAG'][4] = EnumEntry('MAV_MODE_FLAG_AUTO_ENABLED', '''0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.''') +MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items. +enums['MAV_MODE_FLAG'][8] = EnumEntry('MAV_MODE_FLAG_GUIDED_ENABLED', '''0b00001000 guided mode enabled, system flies MISSIONs / mission items.''') +MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and + # optionally position). It needs however + # further control inputs to move around. +enums['MAV_MODE_FLAG'][16] = EnumEntry('MAV_MODE_FLAG_STABILIZE_ENABLED', '''0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.''') +MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are + # blocked, but internal software is full + # operational. +enums['MAV_MODE_FLAG'][32] = EnumEntry('MAV_MODE_FLAG_HIL_ENABLED', '''0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.''') +MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled. +enums['MAV_MODE_FLAG'][64] = EnumEntry('MAV_MODE_FLAG_MANUAL_INPUT_ENABLED', '''0b01000000 remote control input is enabled.''') +MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can + # start. Ready to fly. +enums['MAV_MODE_FLAG'][128] = EnumEntry('MAV_MODE_FLAG_SAFETY_ARMED', '''0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.''') +MAV_MODE_FLAG_ENUM_END = 129 # +enums['MAV_MODE_FLAG'][129] = EnumEntry('MAV_MODE_FLAG_ENUM_END', '''''') + +# MAV_MODE_FLAG_DECODE_POSITION +enums['MAV_MODE_FLAG_DECODE_POSITION'] = {} +MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001 +enums['MAV_MODE_FLAG_DECODE_POSITION'][1] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE', '''Eighth bit: 00000001''') +MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010 +enums['MAV_MODE_FLAG_DECODE_POSITION'][2] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_TEST', '''Seventh bit: 00000010''') +MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100 +enums['MAV_MODE_FLAG_DECODE_POSITION'][4] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_AUTO', '''Sixt bit: 00000100''') +MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][8] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_GUIDED', '''Fifth bit: 00001000''') +MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][16] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_STABILIZE', '''Fourth bit: 00010000''') +MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][32] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_HIL', '''Third bit: 00100000''') +MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][64] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_MANUAL', '''Second bit: 01000000''') +MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][128] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_SAFETY', '''First bit: 10000000''') +MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 # +enums['MAV_MODE_FLAG_DECODE_POSITION'][129] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_ENUM_END', '''''') + +# MAV_GOTO +enums['MAV_GOTO'] = {} +MAV_GOTO_DO_HOLD = 0 # Hold at the current position. +enums['MAV_GOTO'][0] = EnumEntry('MAV_GOTO_DO_HOLD', '''Hold at the current position.''') +MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution. +enums['MAV_GOTO'][1] = EnumEntry('MAV_GOTO_DO_CONTINUE', '''Continue with the next item in mission execution.''') +MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system +enums['MAV_GOTO'][2] = EnumEntry('MAV_GOTO_HOLD_AT_CURRENT_POSITION', '''Hold at the current position of the system''') +MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action +enums['MAV_GOTO'][3] = EnumEntry('MAV_GOTO_HOLD_AT_SPECIFIED_POSITION', '''Hold at the position specified in the parameters of the DO_HOLD action''') +MAV_GOTO_ENUM_END = 4 # +enums['MAV_GOTO'][4] = EnumEntry('MAV_GOTO_ENUM_END', '''''') + +# MAV_MODE +enums['MAV_MODE'] = {} +MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set. +enums['MAV_MODE'][0] = EnumEntry('MAV_MODE_PREFLIGHT', '''System is not ready to fly, booting, calibrating, etc. No flag is set.''') +MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][64] = EnumEntry('MAV_MODE_MANUAL_DISARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][66] = EnumEntry('MAV_MODE_TEST_DISARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][80] = EnumEntry('MAV_MODE_STABILIZE_DISARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][88] = EnumEntry('MAV_MODE_GUIDED_DISARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][92] = EnumEntry('MAV_MODE_AUTO_DISARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][192] = EnumEntry('MAV_MODE_MANUAL_ARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][194] = EnumEntry('MAV_MODE_TEST_ARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][208] = EnumEntry('MAV_MODE_STABILIZE_ARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][216] = EnumEntry('MAV_MODE_GUIDED_ARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][220] = EnumEntry('MAV_MODE_AUTO_ARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_ENUM_END = 221 # +enums['MAV_MODE'][221] = EnumEntry('MAV_MODE_ENUM_END', '''''') + +# MAV_STATE +enums['MAV_STATE'] = {} +MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown. +enums['MAV_STATE'][0] = EnumEntry('MAV_STATE_UNINIT', '''Uninitialized system, state is unknown.''') +MAV_STATE_BOOT = 1 # System is booting up. +enums['MAV_STATE'][1] = EnumEntry('MAV_STATE_BOOT', '''System is booting up.''') +MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready. +enums['MAV_STATE'][2] = EnumEntry('MAV_STATE_CALIBRATING', '''System is calibrating and not flight-ready.''') +MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time. +enums['MAV_STATE'][3] = EnumEntry('MAV_STATE_STANDBY', '''System is grounded and on standby. It can be launched any time.''') +MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged. +enums['MAV_STATE'][4] = EnumEntry('MAV_STATE_ACTIVE', '''System is active and might be already airborne. Motors are engaged.''') +MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate. +enums['MAV_STATE'][5] = EnumEntry('MAV_STATE_CRITICAL', '''System is in a non-normal flight mode. It can however still navigate.''') +MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or + # over the whole airframe. It is in mayday and + # going down. +enums['MAV_STATE'][6] = EnumEntry('MAV_STATE_EMERGENCY', '''System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.''') +MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now. +enums['MAV_STATE'][7] = EnumEntry('MAV_STATE_POWEROFF', '''System just initialized its power-down sequence, will shut down now.''') +MAV_STATE_ENUM_END = 8 # +enums['MAV_STATE'][8] = EnumEntry('MAV_STATE_ENUM_END', '''''') + +# MAV_COMPONENT +enums['MAV_COMPONENT'] = {} +MAV_COMP_ID_ALL = 0 # +enums['MAV_COMPONENT'][0] = EnumEntry('MAV_COMP_ID_ALL', '''''') +MAV_COMP_ID_CAMERA = 100 # +enums['MAV_COMPONENT'][100] = EnumEntry('MAV_COMP_ID_CAMERA', '''''') +MAV_COMP_ID_SERVO1 = 140 # +enums['MAV_COMPONENT'][140] = EnumEntry('MAV_COMP_ID_SERVO1', '''''') +MAV_COMP_ID_SERVO2 = 141 # +enums['MAV_COMPONENT'][141] = EnumEntry('MAV_COMP_ID_SERVO2', '''''') +MAV_COMP_ID_SERVO3 = 142 # +enums['MAV_COMPONENT'][142] = EnumEntry('MAV_COMP_ID_SERVO3', '''''') +MAV_COMP_ID_SERVO4 = 143 # +enums['MAV_COMPONENT'][143] = EnumEntry('MAV_COMP_ID_SERVO4', '''''') +MAV_COMP_ID_SERVO5 = 144 # +enums['MAV_COMPONENT'][144] = EnumEntry('MAV_COMP_ID_SERVO5', '''''') +MAV_COMP_ID_SERVO6 = 145 # +enums['MAV_COMPONENT'][145] = EnumEntry('MAV_COMP_ID_SERVO6', '''''') +MAV_COMP_ID_SERVO7 = 146 # +enums['MAV_COMPONENT'][146] = EnumEntry('MAV_COMP_ID_SERVO7', '''''') +MAV_COMP_ID_SERVO8 = 147 # +enums['MAV_COMPONENT'][147] = EnumEntry('MAV_COMP_ID_SERVO8', '''''') +MAV_COMP_ID_SERVO9 = 148 # +enums['MAV_COMPONENT'][148] = EnumEntry('MAV_COMP_ID_SERVO9', '''''') +MAV_COMP_ID_SERVO10 = 149 # +enums['MAV_COMPONENT'][149] = EnumEntry('MAV_COMP_ID_SERVO10', '''''') +MAV_COMP_ID_SERVO11 = 150 # +enums['MAV_COMPONENT'][150] = EnumEntry('MAV_COMP_ID_SERVO11', '''''') +MAV_COMP_ID_SERVO12 = 151 # +enums['MAV_COMPONENT'][151] = EnumEntry('MAV_COMP_ID_SERVO12', '''''') +MAV_COMP_ID_SERVO13 = 152 # +enums['MAV_COMPONENT'][152] = EnumEntry('MAV_COMP_ID_SERVO13', '''''') +MAV_COMP_ID_SERVO14 = 153 # +enums['MAV_COMPONENT'][153] = EnumEntry('MAV_COMP_ID_SERVO14', '''''') +MAV_COMP_ID_GIMBAL = 154 # +enums['MAV_COMPONENT'][154] = EnumEntry('MAV_COMP_ID_GIMBAL', '''''') +MAV_COMP_ID_LOG = 155 # +enums['MAV_COMPONENT'][155] = EnumEntry('MAV_COMP_ID_LOG', '''''') +MAV_COMP_ID_ADSB = 156 # +enums['MAV_COMPONENT'][156] = EnumEntry('MAV_COMP_ID_ADSB', '''''') +MAV_COMP_ID_OSD = 157 # On Screen Display (OSD) devices for video links +enums['MAV_COMPONENT'][157] = EnumEntry('MAV_COMP_ID_OSD', '''On Screen Display (OSD) devices for video links''') +MAV_COMP_ID_PERIPHERAL = 158 # Generic autopilot peripheral component ID. Meant for devices that do + # not implement the parameter sub-protocol +enums['MAV_COMPONENT'][158] = EnumEntry('MAV_COMP_ID_PERIPHERAL', '''Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol''') +MAV_COMP_ID_MAPPER = 180 # +enums['MAV_COMPONENT'][180] = EnumEntry('MAV_COMP_ID_MAPPER', '''''') +MAV_COMP_ID_MISSIONPLANNER = 190 # +enums['MAV_COMPONENT'][190] = EnumEntry('MAV_COMP_ID_MISSIONPLANNER', '''''') +MAV_COMP_ID_PATHPLANNER = 195 # +enums['MAV_COMPONENT'][195] = EnumEntry('MAV_COMP_ID_PATHPLANNER', '''''') +MAV_COMP_ID_IMU = 200 # +enums['MAV_COMPONENT'][200] = EnumEntry('MAV_COMP_ID_IMU', '''''') +MAV_COMP_ID_IMU_2 = 201 # +enums['MAV_COMPONENT'][201] = EnumEntry('MAV_COMP_ID_IMU_2', '''''') +MAV_COMP_ID_IMU_3 = 202 # +enums['MAV_COMPONENT'][202] = EnumEntry('MAV_COMP_ID_IMU_3', '''''') +MAV_COMP_ID_GPS = 220 # +enums['MAV_COMPONENT'][220] = EnumEntry('MAV_COMP_ID_GPS', '''''') +MAV_COMP_ID_UDP_BRIDGE = 240 # +enums['MAV_COMPONENT'][240] = EnumEntry('MAV_COMP_ID_UDP_BRIDGE', '''''') +MAV_COMP_ID_UART_BRIDGE = 241 # +enums['MAV_COMPONENT'][241] = EnumEntry('MAV_COMP_ID_UART_BRIDGE', '''''') +MAV_COMP_ID_SYSTEM_CONTROL = 250 # +enums['MAV_COMPONENT'][250] = EnumEntry('MAV_COMP_ID_SYSTEM_CONTROL', '''''') +MAV_COMPONENT_ENUM_END = 251 # +enums['MAV_COMPONENT'][251] = EnumEntry('MAV_COMPONENT_ENUM_END', '''''') + +# MAV_SYS_STATUS_SENSOR +enums['MAV_SYS_STATUS_SENSOR'] = {} +MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 # 0x01 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][1] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO', '''0x01 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 # 0x02 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][2] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL', '''0x02 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG = 4 # 0x04 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][4] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG', '''0x04 3D magnetometer''') +MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 # 0x08 absolute pressure +enums['MAV_SYS_STATUS_SENSOR'][8] = EnumEntry('MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE', '''0x08 absolute pressure''') +MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 # 0x10 differential pressure +enums['MAV_SYS_STATUS_SENSOR'][16] = EnumEntry('MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE', '''0x10 differential pressure''') +MAV_SYS_STATUS_SENSOR_GPS = 32 # 0x20 GPS +enums['MAV_SYS_STATUS_SENSOR'][32] = EnumEntry('MAV_SYS_STATUS_SENSOR_GPS', '''0x20 GPS''') +MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 # 0x40 optical flow +enums['MAV_SYS_STATUS_SENSOR'][64] = EnumEntry('MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW', '''0x40 optical flow''') +MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 # 0x80 computer vision position +enums['MAV_SYS_STATUS_SENSOR'][128] = EnumEntry('MAV_SYS_STATUS_SENSOR_VISION_POSITION', '''0x80 computer vision position''') +MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 # 0x100 laser based position +enums['MAV_SYS_STATUS_SENSOR'][256] = EnumEntry('MAV_SYS_STATUS_SENSOR_LASER_POSITION', '''0x100 laser based position''') +MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 # 0x200 external ground truth (Vicon or Leica) +enums['MAV_SYS_STATUS_SENSOR'][512] = EnumEntry('MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH', '''0x200 external ground truth (Vicon or Leica)''') +MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 # 0x400 3D angular rate control +enums['MAV_SYS_STATUS_SENSOR'][1024] = EnumEntry('MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL', '''0x400 3D angular rate control''') +MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 # 0x800 attitude stabilization +enums['MAV_SYS_STATUS_SENSOR'][2048] = EnumEntry('MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION', '''0x800 attitude stabilization''') +MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 # 0x1000 yaw position +enums['MAV_SYS_STATUS_SENSOR'][4096] = EnumEntry('MAV_SYS_STATUS_SENSOR_YAW_POSITION', '''0x1000 yaw position''') +MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 # 0x2000 z/altitude control +enums['MAV_SYS_STATUS_SENSOR'][8192] = EnumEntry('MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL', '''0x2000 z/altitude control''') +MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 # 0x4000 x/y position control +enums['MAV_SYS_STATUS_SENSOR'][16384] = EnumEntry('MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL', '''0x4000 x/y position control''') +MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 # 0x8000 motor outputs / control +enums['MAV_SYS_STATUS_SENSOR'][32768] = EnumEntry('MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS', '''0x8000 motor outputs / control''') +MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 # 0x10000 rc receiver +enums['MAV_SYS_STATUS_SENSOR'][65536] = EnumEntry('MAV_SYS_STATUS_SENSOR_RC_RECEIVER', '''0x10000 rc receiver''') +MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 # 0x20000 2nd 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][131072] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO2', '''0x20000 2nd 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 # 0x40000 2nd 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][262144] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL2', '''0x40000 2nd 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 # 0x80000 2nd 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][524288] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG2', '''0x80000 2nd 3D magnetometer''') +MAV_SYS_STATUS_GEOFENCE = 1048576 # 0x100000 geofence +enums['MAV_SYS_STATUS_SENSOR'][1048576] = EnumEntry('MAV_SYS_STATUS_GEOFENCE', '''0x100000 geofence''') +MAV_SYS_STATUS_AHRS = 2097152 # 0x200000 AHRS subsystem health +enums['MAV_SYS_STATUS_SENSOR'][2097152] = EnumEntry('MAV_SYS_STATUS_AHRS', '''0x200000 AHRS subsystem health''') +MAV_SYS_STATUS_TERRAIN = 4194304 # 0x400000 Terrain subsystem health +enums['MAV_SYS_STATUS_SENSOR'][4194304] = EnumEntry('MAV_SYS_STATUS_TERRAIN', '''0x400000 Terrain subsystem health''') +MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 # 0x800000 Motors are reversed +enums['MAV_SYS_STATUS_SENSOR'][8388608] = EnumEntry('MAV_SYS_STATUS_REVERSE_MOTOR', '''0x800000 Motors are reversed''') +MAV_SYS_STATUS_SENSOR_ENUM_END = 8388609 # +enums['MAV_SYS_STATUS_SENSOR'][8388609] = EnumEntry('MAV_SYS_STATUS_SENSOR_ENUM_END', '''''') + +# MAV_FRAME +enums['MAV_FRAME'] = {} +MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude, second value / y: longitude, third + # value / z: positive altitude over mean sea + # level (MSL) +enums['MAV_FRAME'][0] = EnumEntry('MAV_FRAME_GLOBAL', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down). +enums['MAV_FRAME'][1] = EnumEntry('MAV_FRAME_LOCAL_NED', '''Local coordinate frame, Z-up (x: north, y: east, z: down).''') +MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command. +enums['MAV_FRAME'][2] = EnumEntry('MAV_FRAME_MISSION', '''NOT a coordinate frame, indicates a mission command.''') +MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude, second + # value / y: longitude, third value / z: + # positive altitude with 0 being at the + # altitude of the home location. +enums['MAV_FRAME'][3] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up) +enums['MAV_FRAME'][4] = EnumEntry('MAV_FRAME_LOCAL_ENU', '''Local coordinate frame, Z-down (x: east, y: north, z: up)''') +MAV_FRAME_GLOBAL_INT = 5 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude in degrees*1.0e-7, second value / + # y: longitude in degrees*1.0e-7, third value + # / z: positive altitude over mean sea level + # (MSL) +enums['MAV_FRAME'][5] = EnumEntry('MAV_FRAME_GLOBAL_INT', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude with 0 being at the altitude of the + # home location. +enums['MAV_FRAME'][6] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT_INT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame + # should be added to the current local frame + # position. +enums['MAV_FRAME'][7] = EnumEntry('MAV_FRAME_LOCAL_OFFSET_NED', '''Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.''') +MAV_FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control + # is externalized - e.g. useful to command 2 + # m/s^2 acceleration to the right. +enums['MAV_FRAME'][8] = EnumEntry('MAV_FRAME_BODY_NED', '''Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.''') +MAV_FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the + # current flight path, to avoid an obstacle - + # e.g. useful to command 2 m/s^2 acceleration + # to the east. +enums['MAV_FRAME'][9] = EnumEntry('MAV_FRAME_BODY_OFFSET_NED', '''Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees, second value / y: longitude in + # degrees, third value / z: positive altitude + # in meters with 0 being at ground level in + # terrain model. +enums['MAV_FRAME'][10] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude in meters with 0 being at ground + # level in terrain model. +enums['MAV_FRAME'][11] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT_INT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_ENUM_END = 12 # +enums['MAV_FRAME'][12] = EnumEntry('MAV_FRAME_ENUM_END', '''''') + +# MAVLINK_DATA_STREAM_TYPE +enums['MAVLINK_DATA_STREAM_TYPE'] = {} +MAVLINK_DATA_STREAM_IMG_JPEG = 1 # +enums['MAVLINK_DATA_STREAM_TYPE'][1] = EnumEntry('MAVLINK_DATA_STREAM_IMG_JPEG', '''''') +MAVLINK_DATA_STREAM_IMG_BMP = 2 # +enums['MAVLINK_DATA_STREAM_TYPE'][2] = EnumEntry('MAVLINK_DATA_STREAM_IMG_BMP', '''''') +MAVLINK_DATA_STREAM_IMG_RAW8U = 3 # +enums['MAVLINK_DATA_STREAM_TYPE'][3] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW8U', '''''') +MAVLINK_DATA_STREAM_IMG_RAW32U = 4 # +enums['MAVLINK_DATA_STREAM_TYPE'][4] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW32U', '''''') +MAVLINK_DATA_STREAM_IMG_PGM = 5 # +enums['MAVLINK_DATA_STREAM_TYPE'][5] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PGM', '''''') +MAVLINK_DATA_STREAM_IMG_PNG = 6 # +enums['MAVLINK_DATA_STREAM_TYPE'][6] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PNG', '''''') +MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 # +enums['MAVLINK_DATA_STREAM_TYPE'][7] = EnumEntry('MAVLINK_DATA_STREAM_TYPE_ENUM_END', '''''') + +# FENCE_ACTION +enums['FENCE_ACTION'] = {} +FENCE_ACTION_NONE = 0 # Disable fenced mode +enums['FENCE_ACTION'][0] = EnumEntry('FENCE_ACTION_NONE', '''Disable fenced mode''') +FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0) +enums['FENCE_ACTION'][1] = EnumEntry('FENCE_ACTION_GUIDED', '''Switched to guided mode to return point (fence point 0)''') +FENCE_ACTION_REPORT = 2 # Report fence breach, but don't take action +enums['FENCE_ACTION'][2] = EnumEntry('FENCE_ACTION_REPORT', '''Report fence breach, but don't take action''') +FENCE_ACTION_GUIDED_THR_PASS = 3 # Switched to guided mode to return point (fence point 0) with manual + # throttle control +enums['FENCE_ACTION'][3] = EnumEntry('FENCE_ACTION_GUIDED_THR_PASS', '''Switched to guided mode to return point (fence point 0) with manual throttle control''') +FENCE_ACTION_ENUM_END = 4 # +enums['FENCE_ACTION'][4] = EnumEntry('FENCE_ACTION_ENUM_END', '''''') + +# FENCE_BREACH +enums['FENCE_BREACH'] = {} +FENCE_BREACH_NONE = 0 # No last fence breach +enums['FENCE_BREACH'][0] = EnumEntry('FENCE_BREACH_NONE', '''No last fence breach''') +FENCE_BREACH_MINALT = 1 # Breached minimum altitude +enums['FENCE_BREACH'][1] = EnumEntry('FENCE_BREACH_MINALT', '''Breached minimum altitude''') +FENCE_BREACH_MAXALT = 2 # Breached maximum altitude +enums['FENCE_BREACH'][2] = EnumEntry('FENCE_BREACH_MAXALT', '''Breached maximum altitude''') +FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary +enums['FENCE_BREACH'][3] = EnumEntry('FENCE_BREACH_BOUNDARY', '''Breached fence boundary''') +FENCE_BREACH_ENUM_END = 4 # +enums['FENCE_BREACH'][4] = EnumEntry('FENCE_BREACH_ENUM_END', '''''') + +# MAV_MOUNT_MODE +enums['MAV_MOUNT_MODE'] = {} +MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permant memory and + # stop stabilization +enums['MAV_MOUNT_MODE'][0] = EnumEntry('MAV_MOUNT_MODE_RETRACT', '''Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization''') +MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +enums['MAV_MOUNT_MODE'][1] = EnumEntry('MAV_MOUNT_MODE_NEUTRAL', '''Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.''') +MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][2] = EnumEntry('MAV_MOUNT_MODE_MAVLINK_TARGETING', '''Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][3] = EnumEntry('MAV_MOUNT_MODE_RC_TARGETING', '''Load neutral position and start RC Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt +enums['MAV_MOUNT_MODE'][4] = EnumEntry('MAV_MOUNT_MODE_GPS_POINT', '''Load neutral position and start to point to Lat,Lon,Alt''') +MAV_MOUNT_MODE_ENUM_END = 5 # +enums['MAV_MOUNT_MODE'][5] = EnumEntry('MAV_MOUNT_MODE_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_SENS_POWER = 201 +MAVLINK_MSG_ID_SENS_MPPT = 202 +MAVLINK_MSG_ID_ASLCTRL_DATA = 203 +MAVLINK_MSG_ID_ASLCTRL_DEBUG = 204 +MAVLINK_MSG_ID_ASLUAV_STATUS = 205 +MAVLINK_MSG_ID_EKF_EXT = 206 +MAVLINK_MSG_ID_ASL_OBCTRL = 207 +MAVLINK_MSG_ID_SENS_ATMOS = 208 +MAVLINK_MSG_ID_SENS_BATMON = 209 +MAVLINK_MSG_ID_FW_SOARING_DATA = 210 +MAVLINK_MSG_ID_SENSORPOD_STATUS = 211 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_sens_power_message(MAVLink_message): + ''' + Voltage and current sensor data + ''' + id = MAVLINK_MSG_ID_SENS_POWER + name = 'SENS_POWER' + fieldnames = ['adc121_vspb_volt', 'adc121_cspb_amp', 'adc121_cs1_amp', 'adc121_cs2_amp'] + ordered_fieldnames = [ 'adc121_vspb_volt', 'adc121_cspb_amp', 'adc121_cs1_amp', 'adc121_cs2_amp' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/ASLUAV.xml b/pymavlink/dialects/v10/ASLUAV.xml new file mode 100644 index 0000000..0c3e394 --- /dev/null +++ b/pymavlink/dialects/v10/ASLUAV.xml @@ -0,0 +1,176 @@ + + + + + common.xml + + + + + Mission command to reset Maximum Power Point Tracker (MPPT) + MPPT number + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a power cycle on payload + Complete power cycle + VISensor power cycle + Empty + Empty + Empty + Empty + Empty + + + + + + Voltage and current sensor data + Power board voltage sensor reading in volts + Power board current sensor reading in amps + Board current sensor 1 reading in amps + Board current sensor 2 reading in amps + + + Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking + MPPT last timestamp + MPPT1 voltage + MPPT1 current + MPPT1 pwm + MPPT1 status + MPPT2 voltage + MPPT2 current + MPPT2 pwm + MPPT2 status + MPPT3 voltage + MPPT3 current + MPPT3 pwm + MPPT3 status + + + ASL-fixed-wing controller data + Timestamp + ASLCTRL control-mode (manual, stabilized, auto, etc...) + See sourcecode for a description of these values... + + + Pitch angle [deg] + Pitch angle reference[deg] + + + + + + + Airspeed reference [m/s] + + Yaw angle [deg] + Yaw angle reference[deg] + Roll angle [deg] + Roll angle reference[deg] + + + + + + + + + ASL-fixed-wing controller debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + + + Extended state information for ASLUAVs + Status of the position-indicator LEDs + Status of the IRIDIUM satellite communication system + Status vector for up to 8 servos + Motor RPM + + + + Extended EKF state estimates for ASLUAVs + Time since system start [us] + Magnitude of wind velocity (in lateral inertial plane) [m/s] + Wind heading angle from North [rad] + Z (Down) component of inertial wind velocity [m/s] + Magnitude of air velocity [m/s] + Sideslip angle [rad] + Angle of attack [rad] + + + Off-board controls/commands for ASLUAVs + Time since system start [us] + Elevator command [~] + Throttle command [~] + Throttle 2 command [~] + Left aileron command [~] + Right aileron command [~] + Rudder command [~] + Off-board computer status + + + Atmospheric sensors (temperature, humidity, ...) + Ambient temperature [degrees Celsius] + Relative humidity [%] + + + Battery pack monitoring data for Li-Ion batteries + Battery pack temperature in [deg C] + Battery pack voltage in [mV] + Battery pack current in [mA] + Battery pack state-of-charge + Battery monitor status report bits in Hex + Battery monitor serial number in Hex + Battery monitor sensor host FET control in Hex + Battery pack cell 1 voltage in [mV] + Battery pack cell 2 voltage in [mV] + Battery pack cell 3 voltage in [mV] + Battery pack cell 4 voltage in [mV] + Battery pack cell 5 voltage in [mV] + Battery pack cell 6 voltage in [mV] + + + Fixed-wing soaring (i.e. thermal seeking) data + Timestamp [ms] + Timestamp since last mode change[ms] + Updraft speed at current/local airplane position [m/s] + Thermal core updraft strength [m/s] + Thermal radius [m] + Thermal center latitude [deg] + Thermal center longitude [deg] + Variance W + Variance R + Variance Lat + Variance Lon + Suggested loiter radius [m] + Control Mode [-] + Data valid [-] + + + Monitoring of sensorpod status + Timestamp in linuxtime [ms] (since 1.1.1970) + Rate of ROS topic 1 + Rate of ROS topic 2 + Rate of ROS topic 3 + Rate of ROS topic 4 + Number of recording nodes + Temperature of sensorpod CPU in [deg C] + Free space available in recordings directory in [Gb] * 1e2 + + + diff --git a/pymavlink/dialects/v10/__init__.py b/pymavlink/dialects/v10/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/pymavlink/dialects/v10/ardupilotmega.py b/pymavlink/dialects/v10/ardupilotmega.py new file mode 100644 index 0000000..93591de --- /dev/null +++ b/pymavlink/dialects/v10/ardupilotmega.py @@ -0,0 +1,14555 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: ardupilotmega.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "ardupilotmega" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_ALTITUDE_WAIT = 83 # Mission command to wait for an altitude or downwards vertical speed. + # This is meant for high altitude balloon + # launches, allowing the aircraft to be idle + # until either an altitude is reached or a + # negative vertical speed is reached + # (indicating early balloon burst). The wiggle + # time is how often to wiggle the control + # surfaces to prevent them seizing up. +enums['MAV_CMD'][83] = EnumEntry('MAV_CMD_NAV_ALTITUDE_WAIT', '''Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up.''') +enums['MAV_CMD'][83].param[1] = '''altitude (m)''' +enums['MAV_CMD'][83].param[2] = '''descent speed (m/s)''' +enums['MAV_CMD'][83].param[3] = '''Wiggle Time (s)''' +enums['MAV_CMD'][83].param[4] = '''Empty''' +enums['MAV_CMD'][83].param[5] = '''Empty''' +enums['MAV_CMD'][83].param[6] = '''Empty''' +enums['MAV_CMD'][83].param[7] = '''Empty''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_MOTOR_TEST = 209 # Mission command to perform motor test +enums['MAV_CMD'][209] = EnumEntry('MAV_CMD_DO_MOTOR_TEST', '''Mission command to perform motor test''') +enums['MAV_CMD'][209].param[1] = '''motor sequence number (a number from 1 to max number of motors on the vehicle)''' +enums['MAV_CMD'][209].param[2] = '''throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)''' +enums['MAV_CMD'][209].param[3] = '''throttle''' +enums['MAV_CMD'][209].param[4] = '''timeout (in seconds)''' +enums['MAV_CMD'][209].param[5] = '''Empty''' +enums['MAV_CMD'][209].param[6] = '''Empty''' +enums['MAV_CMD'][209].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_GRIPPER = 211 # Mission command to operate EPM gripper +enums['MAV_CMD'][211] = EnumEntry('MAV_CMD_DO_GRIPPER', '''Mission command to operate EPM gripper''') +enums['MAV_CMD'][211].param[1] = '''gripper number (a number from 1 to max number of grippers on the vehicle)''' +enums['MAV_CMD'][211].param[2] = '''gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)''' +enums['MAV_CMD'][211].param[3] = '''Empty''' +enums['MAV_CMD'][211].param[4] = '''Empty''' +enums['MAV_CMD'][211].param[5] = '''Empty''' +enums['MAV_CMD'][211].param[6] = '''Empty''' +enums['MAV_CMD'][211].param[7] = '''Empty''' +MAV_CMD_DO_AUTOTUNE_ENABLE = 212 # Enable/disable autotune +enums['MAV_CMD'][212] = EnumEntry('MAV_CMD_DO_AUTOTUNE_ENABLE', '''Enable/disable autotune''') +enums['MAV_CMD'][212].param[1] = '''enable (1: enable, 0:disable)''' +enums['MAV_CMD'][212].param[2] = '''Empty''' +enums['MAV_CMD'][212].param[3] = '''Empty''' +enums['MAV_CMD'][212].param[4] = '''Empty''' +enums['MAV_CMD'][212].param[5] = '''Empty''' +enums['MAV_CMD'][212].param[6] = '''Empty''' +enums['MAV_CMD'][212].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_POWER_OFF_INITIATED = 42000 # A system wide power-off event has been initiated. +enums['MAV_CMD'][42000] = EnumEntry('MAV_CMD_POWER_OFF_INITIATED', '''A system wide power-off event has been initiated.''') +enums['MAV_CMD'][42000].param[1] = '''Empty''' +enums['MAV_CMD'][42000].param[2] = '''Empty''' +enums['MAV_CMD'][42000].param[3] = '''Empty''' +enums['MAV_CMD'][42000].param[4] = '''Empty''' +enums['MAV_CMD'][42000].param[5] = '''Empty''' +enums['MAV_CMD'][42000].param[6] = '''Empty''' +enums['MAV_CMD'][42000].param[7] = '''Empty''' +MAV_CMD_SOLO_BTN_FLY_CLICK = 42001 # FLY button has been clicked. +enums['MAV_CMD'][42001] = EnumEntry('MAV_CMD_SOLO_BTN_FLY_CLICK', '''FLY button has been clicked.''') +enums['MAV_CMD'][42001].param[1] = '''Empty''' +enums['MAV_CMD'][42001].param[2] = '''Empty''' +enums['MAV_CMD'][42001].param[3] = '''Empty''' +enums['MAV_CMD'][42001].param[4] = '''Empty''' +enums['MAV_CMD'][42001].param[5] = '''Empty''' +enums['MAV_CMD'][42001].param[6] = '''Empty''' +enums['MAV_CMD'][42001].param[7] = '''Empty''' +MAV_CMD_SOLO_BTN_FLY_HOLD = 42002 # FLY button has been held for 1.5 seconds. +enums['MAV_CMD'][42002] = EnumEntry('MAV_CMD_SOLO_BTN_FLY_HOLD', '''FLY button has been held for 1.5 seconds.''') +enums['MAV_CMD'][42002].param[1] = '''Takeoff altitude''' +enums['MAV_CMD'][42002].param[2] = '''Empty''' +enums['MAV_CMD'][42002].param[3] = '''Empty''' +enums['MAV_CMD'][42002].param[4] = '''Empty''' +enums['MAV_CMD'][42002].param[5] = '''Empty''' +enums['MAV_CMD'][42002].param[6] = '''Empty''' +enums['MAV_CMD'][42002].param[7] = '''Empty''' +MAV_CMD_SOLO_BTN_PAUSE_CLICK = 42003 # PAUSE button has been clicked. +enums['MAV_CMD'][42003] = EnumEntry('MAV_CMD_SOLO_BTN_PAUSE_CLICK', '''PAUSE button has been clicked.''') +enums['MAV_CMD'][42003].param[1] = '''1 if Solo is in a shot mode, 0 otherwise''' +enums['MAV_CMD'][42003].param[2] = '''Empty''' +enums['MAV_CMD'][42003].param[3] = '''Empty''' +enums['MAV_CMD'][42003].param[4] = '''Empty''' +enums['MAV_CMD'][42003].param[5] = '''Empty''' +enums['MAV_CMD'][42003].param[6] = '''Empty''' +enums['MAV_CMD'][42003].param[7] = '''Empty''' +MAV_CMD_DO_START_MAG_CAL = 42424 # Initiate a magnetometer calibration +enums['MAV_CMD'][42424] = EnumEntry('MAV_CMD_DO_START_MAG_CAL', '''Initiate a magnetometer calibration''') +enums['MAV_CMD'][42424].param[1] = '''uint8_t bitmask of magnetometers (0 means all)''' +enums['MAV_CMD'][42424].param[2] = '''Automatically retry on failure (0=no retry, 1=retry).''' +enums['MAV_CMD'][42424].param[3] = '''Save without user input (0=require input, 1=autosave).''' +enums['MAV_CMD'][42424].param[4] = '''Delay (seconds)''' +enums['MAV_CMD'][42424].param[5] = '''Autoreboot (0=user reboot, 1=autoreboot)''' +enums['MAV_CMD'][42424].param[6] = '''Empty''' +enums['MAV_CMD'][42424].param[7] = '''Empty''' +MAV_CMD_DO_ACCEPT_MAG_CAL = 42425 # Initiate a magnetometer calibration +enums['MAV_CMD'][42425] = EnumEntry('MAV_CMD_DO_ACCEPT_MAG_CAL', '''Initiate a magnetometer calibration''') +enums['MAV_CMD'][42425].param[1] = '''uint8_t bitmask of magnetometers (0 means all)''' +enums['MAV_CMD'][42425].param[2] = '''Empty''' +enums['MAV_CMD'][42425].param[3] = '''Empty''' +enums['MAV_CMD'][42425].param[4] = '''Empty''' +enums['MAV_CMD'][42425].param[5] = '''Empty''' +enums['MAV_CMD'][42425].param[6] = '''Empty''' +enums['MAV_CMD'][42425].param[7] = '''Empty''' +MAV_CMD_DO_CANCEL_MAG_CAL = 42426 # Cancel a running magnetometer calibration +enums['MAV_CMD'][42426] = EnumEntry('MAV_CMD_DO_CANCEL_MAG_CAL', '''Cancel a running magnetometer calibration''') +enums['MAV_CMD'][42426].param[1] = '''uint8_t bitmask of magnetometers (0 means all)''' +enums['MAV_CMD'][42426].param[2] = '''Empty''' +enums['MAV_CMD'][42426].param[3] = '''Empty''' +enums['MAV_CMD'][42426].param[4] = '''Empty''' +enums['MAV_CMD'][42426].param[5] = '''Empty''' +enums['MAV_CMD'][42426].param[6] = '''Empty''' +enums['MAV_CMD'][42426].param[7] = '''Empty''' +MAV_CMD_SET_FACTORY_TEST_MODE = 42427 # Command autopilot to get into factory test/diagnostic mode +enums['MAV_CMD'][42427] = EnumEntry('MAV_CMD_SET_FACTORY_TEST_MODE', '''Command autopilot to get into factory test/diagnostic mode''') +enums['MAV_CMD'][42427].param[1] = '''0 means get out of test mode, 1 means get into test mode''' +enums['MAV_CMD'][42427].param[2] = '''Empty''' +enums['MAV_CMD'][42427].param[3] = '''Empty''' +enums['MAV_CMD'][42427].param[4] = '''Empty''' +enums['MAV_CMD'][42427].param[5] = '''Empty''' +enums['MAV_CMD'][42427].param[6] = '''Empty''' +enums['MAV_CMD'][42427].param[7] = '''Empty''' +MAV_CMD_DO_SEND_BANNER = 42428 # Reply with the version banner +enums['MAV_CMD'][42428] = EnumEntry('MAV_CMD_DO_SEND_BANNER', '''Reply with the version banner''') +enums['MAV_CMD'][42428].param[1] = '''Empty''' +enums['MAV_CMD'][42428].param[2] = '''Empty''' +enums['MAV_CMD'][42428].param[3] = '''Empty''' +enums['MAV_CMD'][42428].param[4] = '''Empty''' +enums['MAV_CMD'][42428].param[5] = '''Empty''' +enums['MAV_CMD'][42428].param[6] = '''Empty''' +enums['MAV_CMD'][42428].param[7] = '''Empty''' +MAV_CMD_GIMBAL_RESET = 42501 # Causes the gimbal to reset and boot as if it was just powered on +enums['MAV_CMD'][42501] = EnumEntry('MAV_CMD_GIMBAL_RESET', '''Causes the gimbal to reset and boot as if it was just powered on''') +enums['MAV_CMD'][42501].param[1] = '''Empty''' +enums['MAV_CMD'][42501].param[2] = '''Empty''' +enums['MAV_CMD'][42501].param[3] = '''Empty''' +enums['MAV_CMD'][42501].param[4] = '''Empty''' +enums['MAV_CMD'][42501].param[5] = '''Empty''' +enums['MAV_CMD'][42501].param[6] = '''Empty''' +enums['MAV_CMD'][42501].param[7] = '''Empty''' +MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS = 42502 # Reports progress and success or failure of gimbal axis calibration + # procedure +enums['MAV_CMD'][42502] = EnumEntry('MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS', '''Reports progress and success or failure of gimbal axis calibration procedure''') +enums['MAV_CMD'][42502].param[1] = '''Gimbal axis we're reporting calibration progress for''' +enums['MAV_CMD'][42502].param[2] = '''Current calibration progress for this axis, 0x64=100%''' +enums['MAV_CMD'][42502].param[3] = '''Status of the calibration''' +enums['MAV_CMD'][42502].param[4] = '''Empty''' +enums['MAV_CMD'][42502].param[5] = '''Empty''' +enums['MAV_CMD'][42502].param[6] = '''Empty''' +enums['MAV_CMD'][42502].param[7] = '''Empty''' +MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION = 42503 # Starts commutation calibration on the gimbal +enums['MAV_CMD'][42503] = EnumEntry('MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION', '''Starts commutation calibration on the gimbal''') +enums['MAV_CMD'][42503].param[1] = '''Empty''' +enums['MAV_CMD'][42503].param[2] = '''Empty''' +enums['MAV_CMD'][42503].param[3] = '''Empty''' +enums['MAV_CMD'][42503].param[4] = '''Empty''' +enums['MAV_CMD'][42503].param[5] = '''Empty''' +enums['MAV_CMD'][42503].param[6] = '''Empty''' +enums['MAV_CMD'][42503].param[7] = '''Empty''' +MAV_CMD_GIMBAL_FULL_RESET = 42505 # Erases gimbal application and parameters +enums['MAV_CMD'][42505] = EnumEntry('MAV_CMD_GIMBAL_FULL_RESET', '''Erases gimbal application and parameters''') +enums['MAV_CMD'][42505].param[1] = '''Magic number''' +enums['MAV_CMD'][42505].param[2] = '''Magic number''' +enums['MAV_CMD'][42505].param[3] = '''Magic number''' +enums['MAV_CMD'][42505].param[4] = '''Magic number''' +enums['MAV_CMD'][42505].param[5] = '''Magic number''' +enums['MAV_CMD'][42505].param[6] = '''Magic number''' +enums['MAV_CMD'][42505].param[7] = '''Magic number''' +MAV_CMD_ENUM_END = 42506 # +enums['MAV_CMD'][42506] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# LIMITS_STATE +enums['LIMITS_STATE'] = {} +LIMITS_INIT = 0 # pre-initialization +enums['LIMITS_STATE'][0] = EnumEntry('LIMITS_INIT', '''pre-initialization''') +LIMITS_DISABLED = 1 # disabled +enums['LIMITS_STATE'][1] = EnumEntry('LIMITS_DISABLED', '''disabled''') +LIMITS_ENABLED = 2 # checking limits +enums['LIMITS_STATE'][2] = EnumEntry('LIMITS_ENABLED', '''checking limits''') +LIMITS_TRIGGERED = 3 # a limit has been breached +enums['LIMITS_STATE'][3] = EnumEntry('LIMITS_TRIGGERED', '''a limit has been breached''') +LIMITS_RECOVERING = 4 # taking action eg. RTL +enums['LIMITS_STATE'][4] = EnumEntry('LIMITS_RECOVERING', '''taking action eg. RTL''') +LIMITS_RECOVERED = 5 # we're no longer in breach of a limit +enums['LIMITS_STATE'][5] = EnumEntry('LIMITS_RECOVERED', '''we're no longer in breach of a limit''') +LIMITS_STATE_ENUM_END = 6 # +enums['LIMITS_STATE'][6] = EnumEntry('LIMITS_STATE_ENUM_END', '''''') + +# LIMIT_MODULE +enums['LIMIT_MODULE'] = {} +LIMIT_GPSLOCK = 1 # pre-initialization +enums['LIMIT_MODULE'][1] = EnumEntry('LIMIT_GPSLOCK', '''pre-initialization''') +LIMIT_GEOFENCE = 2 # disabled +enums['LIMIT_MODULE'][2] = EnumEntry('LIMIT_GEOFENCE', '''disabled''') +LIMIT_ALTITUDE = 4 # checking limits +enums['LIMIT_MODULE'][4] = EnumEntry('LIMIT_ALTITUDE', '''checking limits''') +LIMIT_MODULE_ENUM_END = 5 # +enums['LIMIT_MODULE'][5] = EnumEntry('LIMIT_MODULE_ENUM_END', '''''') + +# RALLY_FLAGS +enums['RALLY_FLAGS'] = {} +FAVORABLE_WIND = 1 # Flag set when requiring favorable winds for landing. +enums['RALLY_FLAGS'][1] = EnumEntry('FAVORABLE_WIND', '''Flag set when requiring favorable winds for landing.''') +LAND_IMMEDIATELY = 2 # Flag set when plane is to immediately descend to break altitude and + # land without GCS intervention. Flag not set + # when plane is to loiter at Rally point until + # commanded to land. +enums['RALLY_FLAGS'][2] = EnumEntry('LAND_IMMEDIATELY', '''Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land.''') +RALLY_FLAGS_ENUM_END = 3 # +enums['RALLY_FLAGS'][3] = EnumEntry('RALLY_FLAGS_ENUM_END', '''''') + +# PARACHUTE_ACTION +enums['PARACHUTE_ACTION'] = {} +PARACHUTE_DISABLE = 0 # Disable parachute release +enums['PARACHUTE_ACTION'][0] = EnumEntry('PARACHUTE_DISABLE', '''Disable parachute release''') +PARACHUTE_ENABLE = 1 # Enable parachute release +enums['PARACHUTE_ACTION'][1] = EnumEntry('PARACHUTE_ENABLE', '''Enable parachute release''') +PARACHUTE_RELEASE = 2 # Release parachute +enums['PARACHUTE_ACTION'][2] = EnumEntry('PARACHUTE_RELEASE', '''Release parachute''') +PARACHUTE_ACTION_ENUM_END = 3 # +enums['PARACHUTE_ACTION'][3] = EnumEntry('PARACHUTE_ACTION_ENUM_END', '''''') + +# MOTOR_TEST_THROTTLE_TYPE +enums['MOTOR_TEST_THROTTLE_TYPE'] = {} +MOTOR_TEST_THROTTLE_PERCENT = 0 # throttle as a percentage from 0 ~ 100 +enums['MOTOR_TEST_THROTTLE_TYPE'][0] = EnumEntry('MOTOR_TEST_THROTTLE_PERCENT', '''throttle as a percentage from 0 ~ 100''') +MOTOR_TEST_THROTTLE_PWM = 1 # throttle as an absolute PWM value (normally in range of 1000~2000) +enums['MOTOR_TEST_THROTTLE_TYPE'][1] = EnumEntry('MOTOR_TEST_THROTTLE_PWM', '''throttle as an absolute PWM value (normally in range of 1000~2000)''') +MOTOR_TEST_THROTTLE_PILOT = 2 # throttle pass-through from pilot's transmitter +enums['MOTOR_TEST_THROTTLE_TYPE'][2] = EnumEntry('MOTOR_TEST_THROTTLE_PILOT', '''throttle pass-through from pilot's transmitter''') +MOTOR_TEST_THROTTLE_TYPE_ENUM_END = 3 # +enums['MOTOR_TEST_THROTTLE_TYPE'][3] = EnumEntry('MOTOR_TEST_THROTTLE_TYPE_ENUM_END', '''''') + +# GRIPPER_ACTIONS +enums['GRIPPER_ACTIONS'] = {} +GRIPPER_ACTION_RELEASE = 0 # gripper release of cargo +enums['GRIPPER_ACTIONS'][0] = EnumEntry('GRIPPER_ACTION_RELEASE', '''gripper release of cargo''') +GRIPPER_ACTION_GRAB = 1 # gripper grabs onto cargo +enums['GRIPPER_ACTIONS'][1] = EnumEntry('GRIPPER_ACTION_GRAB', '''gripper grabs onto cargo''') +GRIPPER_ACTIONS_ENUM_END = 2 # +enums['GRIPPER_ACTIONS'][2] = EnumEntry('GRIPPER_ACTIONS_ENUM_END', '''''') + +# CAMERA_STATUS_TYPES +enums['CAMERA_STATUS_TYPES'] = {} +CAMERA_STATUS_TYPE_HEARTBEAT = 0 # Camera heartbeat, announce camera component ID at 1hz +enums['CAMERA_STATUS_TYPES'][0] = EnumEntry('CAMERA_STATUS_TYPE_HEARTBEAT', '''Camera heartbeat, announce camera component ID at 1hz''') +CAMERA_STATUS_TYPE_TRIGGER = 1 # Camera image triggered +enums['CAMERA_STATUS_TYPES'][1] = EnumEntry('CAMERA_STATUS_TYPE_TRIGGER', '''Camera image triggered''') +CAMERA_STATUS_TYPE_DISCONNECT = 2 # Camera connection lost +enums['CAMERA_STATUS_TYPES'][2] = EnumEntry('CAMERA_STATUS_TYPE_DISCONNECT', '''Camera connection lost''') +CAMERA_STATUS_TYPE_ERROR = 3 # Camera unknown error +enums['CAMERA_STATUS_TYPES'][3] = EnumEntry('CAMERA_STATUS_TYPE_ERROR', '''Camera unknown error''') +CAMERA_STATUS_TYPE_LOWBATT = 4 # Camera battery low. Parameter p1 shows reported voltage +enums['CAMERA_STATUS_TYPES'][4] = EnumEntry('CAMERA_STATUS_TYPE_LOWBATT', '''Camera battery low. Parameter p1 shows reported voltage''') +CAMERA_STATUS_TYPE_LOWSTORE = 5 # Camera storage low. Parameter p1 shows reported shots remaining +enums['CAMERA_STATUS_TYPES'][5] = EnumEntry('CAMERA_STATUS_TYPE_LOWSTORE', '''Camera storage low. Parameter p1 shows reported shots remaining''') +CAMERA_STATUS_TYPE_LOWSTOREV = 6 # Camera storage low. Parameter p1 shows reported video minutes + # remaining +enums['CAMERA_STATUS_TYPES'][6] = EnumEntry('CAMERA_STATUS_TYPE_LOWSTOREV', '''Camera storage low. Parameter p1 shows reported video minutes remaining''') +CAMERA_STATUS_TYPES_ENUM_END = 7 # +enums['CAMERA_STATUS_TYPES'][7] = EnumEntry('CAMERA_STATUS_TYPES_ENUM_END', '''''') + +# CAMERA_FEEDBACK_FLAGS +enums['CAMERA_FEEDBACK_FLAGS'] = {} +CAMERA_FEEDBACK_PHOTO = 0 # Shooting photos, not video +enums['CAMERA_FEEDBACK_FLAGS'][0] = EnumEntry('CAMERA_FEEDBACK_PHOTO', '''Shooting photos, not video''') +CAMERA_FEEDBACK_VIDEO = 1 # Shooting video, not stills +enums['CAMERA_FEEDBACK_FLAGS'][1] = EnumEntry('CAMERA_FEEDBACK_VIDEO', '''Shooting video, not stills''') +CAMERA_FEEDBACK_BADEXPOSURE = 2 # Unable to achieve requested exposure (e.g. shutter speed too low) +enums['CAMERA_FEEDBACK_FLAGS'][2] = EnumEntry('CAMERA_FEEDBACK_BADEXPOSURE', '''Unable to achieve requested exposure (e.g. shutter speed too low)''') +CAMERA_FEEDBACK_CLOSEDLOOP = 3 # Closed loop feedback from camera, we know for sure it has successfully + # taken a picture +enums['CAMERA_FEEDBACK_FLAGS'][3] = EnumEntry('CAMERA_FEEDBACK_CLOSEDLOOP', '''Closed loop feedback from camera, we know for sure it has successfully taken a picture''') +CAMERA_FEEDBACK_OPENLOOP = 4 # Open loop camera, an image trigger has been requested but we can't + # know for sure it has successfully taken a + # picture +enums['CAMERA_FEEDBACK_FLAGS'][4] = EnumEntry('CAMERA_FEEDBACK_OPENLOOP', '''Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture''') +CAMERA_FEEDBACK_FLAGS_ENUM_END = 5 # +enums['CAMERA_FEEDBACK_FLAGS'][5] = EnumEntry('CAMERA_FEEDBACK_FLAGS_ENUM_END', '''''') + +# MAV_MODE_GIMBAL +enums['MAV_MODE_GIMBAL'] = {} +MAV_MODE_GIMBAL_UNINITIALIZED = 0 # Gimbal is powered on but has not started initializing yet +enums['MAV_MODE_GIMBAL'][0] = EnumEntry('MAV_MODE_GIMBAL_UNINITIALIZED', '''Gimbal is powered on but has not started initializing yet''') +MAV_MODE_GIMBAL_CALIBRATING_PITCH = 1 # Gimbal is currently running calibration on the pitch axis +enums['MAV_MODE_GIMBAL'][1] = EnumEntry('MAV_MODE_GIMBAL_CALIBRATING_PITCH', '''Gimbal is currently running calibration on the pitch axis''') +MAV_MODE_GIMBAL_CALIBRATING_ROLL = 2 # Gimbal is currently running calibration on the roll axis +enums['MAV_MODE_GIMBAL'][2] = EnumEntry('MAV_MODE_GIMBAL_CALIBRATING_ROLL', '''Gimbal is currently running calibration on the roll axis''') +MAV_MODE_GIMBAL_CALIBRATING_YAW = 3 # Gimbal is currently running calibration on the yaw axis +enums['MAV_MODE_GIMBAL'][3] = EnumEntry('MAV_MODE_GIMBAL_CALIBRATING_YAW', '''Gimbal is currently running calibration on the yaw axis''') +MAV_MODE_GIMBAL_INITIALIZED = 4 # Gimbal has finished calibrating and initializing, but is relaxed + # pending reception of first rate command from + # copter +enums['MAV_MODE_GIMBAL'][4] = EnumEntry('MAV_MODE_GIMBAL_INITIALIZED', '''Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter''') +MAV_MODE_GIMBAL_ACTIVE = 5 # Gimbal is actively stabilizing +enums['MAV_MODE_GIMBAL'][5] = EnumEntry('MAV_MODE_GIMBAL_ACTIVE', '''Gimbal is actively stabilizing''') +MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT = 6 # Gimbal is relaxed because it missed more than 10 expected rate command + # messages in a row. Gimbal will move back to + # active mode when it receives a new rate + # command +enums['MAV_MODE_GIMBAL'][6] = EnumEntry('MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT', '''Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command''') +MAV_MODE_GIMBAL_ENUM_END = 7 # +enums['MAV_MODE_GIMBAL'][7] = EnumEntry('MAV_MODE_GIMBAL_ENUM_END', '''''') + +# GIMBAL_AXIS +enums['GIMBAL_AXIS'] = {} +GIMBAL_AXIS_YAW = 0 # Gimbal yaw axis +enums['GIMBAL_AXIS'][0] = EnumEntry('GIMBAL_AXIS_YAW', '''Gimbal yaw axis''') +GIMBAL_AXIS_PITCH = 1 # Gimbal pitch axis +enums['GIMBAL_AXIS'][1] = EnumEntry('GIMBAL_AXIS_PITCH', '''Gimbal pitch axis''') +GIMBAL_AXIS_ROLL = 2 # Gimbal roll axis +enums['GIMBAL_AXIS'][2] = EnumEntry('GIMBAL_AXIS_ROLL', '''Gimbal roll axis''') +GIMBAL_AXIS_ENUM_END = 3 # +enums['GIMBAL_AXIS'][3] = EnumEntry('GIMBAL_AXIS_ENUM_END', '''''') + +# GIMBAL_AXIS_CALIBRATION_STATUS +enums['GIMBAL_AXIS_CALIBRATION_STATUS'] = {} +GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS = 0 # Axis calibration is in progress +enums['GIMBAL_AXIS_CALIBRATION_STATUS'][0] = EnumEntry('GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS', '''Axis calibration is in progress''') +GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED = 1 # Axis calibration succeeded +enums['GIMBAL_AXIS_CALIBRATION_STATUS'][1] = EnumEntry('GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED', '''Axis calibration succeeded''') +GIMBAL_AXIS_CALIBRATION_STATUS_FAILED = 2 # Axis calibration failed +enums['GIMBAL_AXIS_CALIBRATION_STATUS'][2] = EnumEntry('GIMBAL_AXIS_CALIBRATION_STATUS_FAILED', '''Axis calibration failed''') +GIMBAL_AXIS_CALIBRATION_STATUS_ENUM_END = 3 # +enums['GIMBAL_AXIS_CALIBRATION_STATUS'][3] = EnumEntry('GIMBAL_AXIS_CALIBRATION_STATUS_ENUM_END', '''''') + +# GIMBAL_AXIS_CALIBRATION_REQUIRED +enums['GIMBAL_AXIS_CALIBRATION_REQUIRED'] = {} +GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN = 0 # Whether or not this axis requires calibration is unknown at this time +enums['GIMBAL_AXIS_CALIBRATION_REQUIRED'][0] = EnumEntry('GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN', '''Whether or not this axis requires calibration is unknown at this time''') +GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE = 1 # This axis requires calibration +enums['GIMBAL_AXIS_CALIBRATION_REQUIRED'][1] = EnumEntry('GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE', '''This axis requires calibration''') +GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE = 2 # This axis does not require calibration +enums['GIMBAL_AXIS_CALIBRATION_REQUIRED'][2] = EnumEntry('GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE', '''This axis does not require calibration''') +GIMBAL_AXIS_CALIBRATION_REQUIRED_ENUM_END = 3 # +enums['GIMBAL_AXIS_CALIBRATION_REQUIRED'][3] = EnumEntry('GIMBAL_AXIS_CALIBRATION_REQUIRED_ENUM_END', '''''') + +# GOPRO_HEARTBEAT_STATUS +enums['GOPRO_HEARTBEAT_STATUS'] = {} +GOPRO_HEARTBEAT_STATUS_DISCONNECTED = 0 # No GoPro connected +enums['GOPRO_HEARTBEAT_STATUS'][0] = EnumEntry('GOPRO_HEARTBEAT_STATUS_DISCONNECTED', '''No GoPro connected''') +GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE = 1 # The detected GoPro is not HeroBus compatible +enums['GOPRO_HEARTBEAT_STATUS'][1] = EnumEntry('GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE', '''The detected GoPro is not HeroBus compatible''') +GOPRO_HEARTBEAT_STATUS_CONNECTED = 2 # A HeroBus compatible GoPro is connected +enums['GOPRO_HEARTBEAT_STATUS'][2] = EnumEntry('GOPRO_HEARTBEAT_STATUS_CONNECTED', '''A HeroBus compatible GoPro is connected''') +GOPRO_HEARTBEAT_STATUS_ERROR = 3 # An unrecoverable error was encountered with the connected GoPro, it + # may require a power cycle +enums['GOPRO_HEARTBEAT_STATUS'][3] = EnumEntry('GOPRO_HEARTBEAT_STATUS_ERROR', '''An unrecoverable error was encountered with the connected GoPro, it may require a power cycle''') +GOPRO_HEARTBEAT_STATUS_ENUM_END = 4 # +enums['GOPRO_HEARTBEAT_STATUS'][4] = EnumEntry('GOPRO_HEARTBEAT_STATUS_ENUM_END', '''''') + +# GOPRO_HEARTBEAT_FLAGS +enums['GOPRO_HEARTBEAT_FLAGS'] = {} +GOPRO_FLAG_RECORDING = 1 # GoPro is currently recording +enums['GOPRO_HEARTBEAT_FLAGS'][1] = EnumEntry('GOPRO_FLAG_RECORDING', '''GoPro is currently recording''') +GOPRO_HEARTBEAT_FLAGS_ENUM_END = 2 # +enums['GOPRO_HEARTBEAT_FLAGS'][2] = EnumEntry('GOPRO_HEARTBEAT_FLAGS_ENUM_END', '''''') + +# GOPRO_REQUEST_STATUS +enums['GOPRO_REQUEST_STATUS'] = {} +GOPRO_REQUEST_SUCCESS = 0 # The write message with ID indicated succeeded +enums['GOPRO_REQUEST_STATUS'][0] = EnumEntry('GOPRO_REQUEST_SUCCESS', '''The write message with ID indicated succeeded''') +GOPRO_REQUEST_FAILED = 1 # The write message with ID indicated failed +enums['GOPRO_REQUEST_STATUS'][1] = EnumEntry('GOPRO_REQUEST_FAILED', '''The write message with ID indicated failed''') +GOPRO_REQUEST_STATUS_ENUM_END = 2 # +enums['GOPRO_REQUEST_STATUS'][2] = EnumEntry('GOPRO_REQUEST_STATUS_ENUM_END', '''''') + +# GOPRO_COMMAND +enums['GOPRO_COMMAND'] = {} +GOPRO_COMMAND_POWER = 0 # (Get/Set) +enums['GOPRO_COMMAND'][0] = EnumEntry('GOPRO_COMMAND_POWER', '''(Get/Set)''') +GOPRO_COMMAND_CAPTURE_MODE = 1 # (Get/Set) +enums['GOPRO_COMMAND'][1] = EnumEntry('GOPRO_COMMAND_CAPTURE_MODE', '''(Get/Set)''') +GOPRO_COMMAND_SHUTTER = 2 # (___/Set) +enums['GOPRO_COMMAND'][2] = EnumEntry('GOPRO_COMMAND_SHUTTER', '''(___/Set)''') +GOPRO_COMMAND_BATTERY = 3 # (Get/___) +enums['GOPRO_COMMAND'][3] = EnumEntry('GOPRO_COMMAND_BATTERY', '''(Get/___)''') +GOPRO_COMMAND_MODEL = 4 # (Get/___) +enums['GOPRO_COMMAND'][4] = EnumEntry('GOPRO_COMMAND_MODEL', '''(Get/___)''') +GOPRO_COMMAND_VIDEO_SETTINGS = 5 # (Get/Set) +enums['GOPRO_COMMAND'][5] = EnumEntry('GOPRO_COMMAND_VIDEO_SETTINGS', '''(Get/Set)''') +GOPRO_COMMAND_LOW_LIGHT = 6 # (Get/Set) +enums['GOPRO_COMMAND'][6] = EnumEntry('GOPRO_COMMAND_LOW_LIGHT', '''(Get/Set)''') +GOPRO_COMMAND_PHOTO_RESOLUTION = 7 # (Get/Set) +enums['GOPRO_COMMAND'][7] = EnumEntry('GOPRO_COMMAND_PHOTO_RESOLUTION', '''(Get/Set)''') +GOPRO_COMMAND_PHOTO_BURST_RATE = 8 # (Get/Set) +enums['GOPRO_COMMAND'][8] = EnumEntry('GOPRO_COMMAND_PHOTO_BURST_RATE', '''(Get/Set)''') +GOPRO_COMMAND_PROTUNE = 9 # (Get/Set) +enums['GOPRO_COMMAND'][9] = EnumEntry('GOPRO_COMMAND_PROTUNE', '''(Get/Set)''') +GOPRO_COMMAND_PROTUNE_WHITE_BALANCE = 10 # (Get/Set) Hero 3+ Only +enums['GOPRO_COMMAND'][10] = EnumEntry('GOPRO_COMMAND_PROTUNE_WHITE_BALANCE', '''(Get/Set) Hero 3+ Only''') +GOPRO_COMMAND_PROTUNE_COLOUR = 11 # (Get/Set) Hero 3+ Only +enums['GOPRO_COMMAND'][11] = EnumEntry('GOPRO_COMMAND_PROTUNE_COLOUR', '''(Get/Set) Hero 3+ Only''') +GOPRO_COMMAND_PROTUNE_GAIN = 12 # (Get/Set) Hero 3+ Only +enums['GOPRO_COMMAND'][12] = EnumEntry('GOPRO_COMMAND_PROTUNE_GAIN', '''(Get/Set) Hero 3+ Only''') +GOPRO_COMMAND_PROTUNE_SHARPNESS = 13 # (Get/Set) Hero 3+ Only +enums['GOPRO_COMMAND'][13] = EnumEntry('GOPRO_COMMAND_PROTUNE_SHARPNESS', '''(Get/Set) Hero 3+ Only''') +GOPRO_COMMAND_PROTUNE_EXPOSURE = 14 # (Get/Set) Hero 3+ Only +enums['GOPRO_COMMAND'][14] = EnumEntry('GOPRO_COMMAND_PROTUNE_EXPOSURE', '''(Get/Set) Hero 3+ Only''') +GOPRO_COMMAND_TIME = 15 # (Get/Set) +enums['GOPRO_COMMAND'][15] = EnumEntry('GOPRO_COMMAND_TIME', '''(Get/Set)''') +GOPRO_COMMAND_CHARGING = 16 # (Get/Set) +enums['GOPRO_COMMAND'][16] = EnumEntry('GOPRO_COMMAND_CHARGING', '''(Get/Set)''') +GOPRO_COMMAND_ENUM_END = 17 # +enums['GOPRO_COMMAND'][17] = EnumEntry('GOPRO_COMMAND_ENUM_END', '''''') + +# GOPRO_CAPTURE_MODE +enums['GOPRO_CAPTURE_MODE'] = {} +GOPRO_CAPTURE_MODE_VIDEO = 0 # Video mode +enums['GOPRO_CAPTURE_MODE'][0] = EnumEntry('GOPRO_CAPTURE_MODE_VIDEO', '''Video mode''') +GOPRO_CAPTURE_MODE_PHOTO = 1 # Photo mode +enums['GOPRO_CAPTURE_MODE'][1] = EnumEntry('GOPRO_CAPTURE_MODE_PHOTO', '''Photo mode''') +GOPRO_CAPTURE_MODE_BURST = 2 # Burst mode, hero 3+ only +enums['GOPRO_CAPTURE_MODE'][2] = EnumEntry('GOPRO_CAPTURE_MODE_BURST', '''Burst mode, hero 3+ only''') +GOPRO_CAPTURE_MODE_TIME_LAPSE = 3 # Time lapse mode, hero 3+ only +enums['GOPRO_CAPTURE_MODE'][3] = EnumEntry('GOPRO_CAPTURE_MODE_TIME_LAPSE', '''Time lapse mode, hero 3+ only''') +GOPRO_CAPTURE_MODE_MULTI_SHOT = 4 # Multi shot mode, hero 4 only +enums['GOPRO_CAPTURE_MODE'][4] = EnumEntry('GOPRO_CAPTURE_MODE_MULTI_SHOT', '''Multi shot mode, hero 4 only''') +GOPRO_CAPTURE_MODE_PLAYBACK = 5 # Playback mode, hero 4 only, silver only except when LCD or HDMI is + # connected to black +enums['GOPRO_CAPTURE_MODE'][5] = EnumEntry('GOPRO_CAPTURE_MODE_PLAYBACK', '''Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black''') +GOPRO_CAPTURE_MODE_SETUP = 6 # Playback mode, hero 4 only +enums['GOPRO_CAPTURE_MODE'][6] = EnumEntry('GOPRO_CAPTURE_MODE_SETUP', '''Playback mode, hero 4 only''') +GOPRO_CAPTURE_MODE_UNKNOWN = 255 # Mode not yet known +enums['GOPRO_CAPTURE_MODE'][255] = EnumEntry('GOPRO_CAPTURE_MODE_UNKNOWN', '''Mode not yet known''') +GOPRO_CAPTURE_MODE_ENUM_END = 256 # +enums['GOPRO_CAPTURE_MODE'][256] = EnumEntry('GOPRO_CAPTURE_MODE_ENUM_END', '''''') + +# GOPRO_RESOLUTION +enums['GOPRO_RESOLUTION'] = {} +GOPRO_RESOLUTION_480p = 0 # 848 x 480 (480p) +enums['GOPRO_RESOLUTION'][0] = EnumEntry('GOPRO_RESOLUTION_480p', '''848 x 480 (480p)''') +GOPRO_RESOLUTION_720p = 1 # 1280 x 720 (720p) +enums['GOPRO_RESOLUTION'][1] = EnumEntry('GOPRO_RESOLUTION_720p', '''1280 x 720 (720p)''') +GOPRO_RESOLUTION_960p = 2 # 1280 x 960 (960p) +enums['GOPRO_RESOLUTION'][2] = EnumEntry('GOPRO_RESOLUTION_960p', '''1280 x 960 (960p)''') +GOPRO_RESOLUTION_1080p = 3 # 1920 x 1080 (1080p) +enums['GOPRO_RESOLUTION'][3] = EnumEntry('GOPRO_RESOLUTION_1080p', '''1920 x 1080 (1080p)''') +GOPRO_RESOLUTION_1440p = 4 # 1920 x 1440 (1440p) +enums['GOPRO_RESOLUTION'][4] = EnumEntry('GOPRO_RESOLUTION_1440p', '''1920 x 1440 (1440p)''') +GOPRO_RESOLUTION_2_7k_17_9 = 5 # 2704 x 1440 (2.7k-17:9) +enums['GOPRO_RESOLUTION'][5] = EnumEntry('GOPRO_RESOLUTION_2_7k_17_9', '''2704 x 1440 (2.7k-17:9)''') +GOPRO_RESOLUTION_2_7k_16_9 = 6 # 2704 x 1524 (2.7k-16:9) +enums['GOPRO_RESOLUTION'][6] = EnumEntry('GOPRO_RESOLUTION_2_7k_16_9', '''2704 x 1524 (2.7k-16:9)''') +GOPRO_RESOLUTION_2_7k_4_3 = 7 # 2704 x 2028 (2.7k-4:3) +enums['GOPRO_RESOLUTION'][7] = EnumEntry('GOPRO_RESOLUTION_2_7k_4_3', '''2704 x 2028 (2.7k-4:3)''') +GOPRO_RESOLUTION_4k_16_9 = 8 # 3840 x 2160 (4k-16:9) +enums['GOPRO_RESOLUTION'][8] = EnumEntry('GOPRO_RESOLUTION_4k_16_9', '''3840 x 2160 (4k-16:9)''') +GOPRO_RESOLUTION_4k_17_9 = 9 # 4096 x 2160 (4k-17:9) +enums['GOPRO_RESOLUTION'][9] = EnumEntry('GOPRO_RESOLUTION_4k_17_9', '''4096 x 2160 (4k-17:9)''') +GOPRO_RESOLUTION_720p_SUPERVIEW = 10 # 1280 x 720 (720p-SuperView) +enums['GOPRO_RESOLUTION'][10] = EnumEntry('GOPRO_RESOLUTION_720p_SUPERVIEW', '''1280 x 720 (720p-SuperView)''') +GOPRO_RESOLUTION_1080p_SUPERVIEW = 11 # 1920 x 1080 (1080p-SuperView) +enums['GOPRO_RESOLUTION'][11] = EnumEntry('GOPRO_RESOLUTION_1080p_SUPERVIEW', '''1920 x 1080 (1080p-SuperView)''') +GOPRO_RESOLUTION_2_7k_SUPERVIEW = 12 # 2704 x 1520 (2.7k-SuperView) +enums['GOPRO_RESOLUTION'][12] = EnumEntry('GOPRO_RESOLUTION_2_7k_SUPERVIEW', '''2704 x 1520 (2.7k-SuperView)''') +GOPRO_RESOLUTION_4k_SUPERVIEW = 13 # 3840 x 2160 (4k-SuperView) +enums['GOPRO_RESOLUTION'][13] = EnumEntry('GOPRO_RESOLUTION_4k_SUPERVIEW', '''3840 x 2160 (4k-SuperView)''') +GOPRO_RESOLUTION_ENUM_END = 14 # +enums['GOPRO_RESOLUTION'][14] = EnumEntry('GOPRO_RESOLUTION_ENUM_END', '''''') + +# GOPRO_FRAME_RATE +enums['GOPRO_FRAME_RATE'] = {} +GOPRO_FRAME_RATE_12 = 0 # 12 FPS +enums['GOPRO_FRAME_RATE'][0] = EnumEntry('GOPRO_FRAME_RATE_12', '''12 FPS''') +GOPRO_FRAME_RATE_15 = 1 # 15 FPS +enums['GOPRO_FRAME_RATE'][1] = EnumEntry('GOPRO_FRAME_RATE_15', '''15 FPS''') +GOPRO_FRAME_RATE_24 = 2 # 24 FPS +enums['GOPRO_FRAME_RATE'][2] = EnumEntry('GOPRO_FRAME_RATE_24', '''24 FPS''') +GOPRO_FRAME_RATE_25 = 3 # 25 FPS +enums['GOPRO_FRAME_RATE'][3] = EnumEntry('GOPRO_FRAME_RATE_25', '''25 FPS''') +GOPRO_FRAME_RATE_30 = 4 # 30 FPS +enums['GOPRO_FRAME_RATE'][4] = EnumEntry('GOPRO_FRAME_RATE_30', '''30 FPS''') +GOPRO_FRAME_RATE_48 = 5 # 48 FPS +enums['GOPRO_FRAME_RATE'][5] = EnumEntry('GOPRO_FRAME_RATE_48', '''48 FPS''') +GOPRO_FRAME_RATE_50 = 6 # 50 FPS +enums['GOPRO_FRAME_RATE'][6] = EnumEntry('GOPRO_FRAME_RATE_50', '''50 FPS''') +GOPRO_FRAME_RATE_60 = 7 # 60 FPS +enums['GOPRO_FRAME_RATE'][7] = EnumEntry('GOPRO_FRAME_RATE_60', '''60 FPS''') +GOPRO_FRAME_RATE_80 = 8 # 80 FPS +enums['GOPRO_FRAME_RATE'][8] = EnumEntry('GOPRO_FRAME_RATE_80', '''80 FPS''') +GOPRO_FRAME_RATE_90 = 9 # 90 FPS +enums['GOPRO_FRAME_RATE'][9] = EnumEntry('GOPRO_FRAME_RATE_90', '''90 FPS''') +GOPRO_FRAME_RATE_100 = 10 # 100 FPS +enums['GOPRO_FRAME_RATE'][10] = EnumEntry('GOPRO_FRAME_RATE_100', '''100 FPS''') +GOPRO_FRAME_RATE_120 = 11 # 120 FPS +enums['GOPRO_FRAME_RATE'][11] = EnumEntry('GOPRO_FRAME_RATE_120', '''120 FPS''') +GOPRO_FRAME_RATE_240 = 12 # 240 FPS +enums['GOPRO_FRAME_RATE'][12] = EnumEntry('GOPRO_FRAME_RATE_240', '''240 FPS''') +GOPRO_FRAME_RATE_12_5 = 13 # 12.5 FPS +enums['GOPRO_FRAME_RATE'][13] = EnumEntry('GOPRO_FRAME_RATE_12_5', '''12.5 FPS''') +GOPRO_FRAME_RATE_ENUM_END = 14 # +enums['GOPRO_FRAME_RATE'][14] = EnumEntry('GOPRO_FRAME_RATE_ENUM_END', '''''') + +# GOPRO_FIELD_OF_VIEW +enums['GOPRO_FIELD_OF_VIEW'] = {} +GOPRO_FIELD_OF_VIEW_WIDE = 0 # 0x00: Wide +enums['GOPRO_FIELD_OF_VIEW'][0] = EnumEntry('GOPRO_FIELD_OF_VIEW_WIDE', '''0x00: Wide''') +GOPRO_FIELD_OF_VIEW_MEDIUM = 1 # 0x01: Medium +enums['GOPRO_FIELD_OF_VIEW'][1] = EnumEntry('GOPRO_FIELD_OF_VIEW_MEDIUM', '''0x01: Medium''') +GOPRO_FIELD_OF_VIEW_NARROW = 2 # 0x02: Narrow +enums['GOPRO_FIELD_OF_VIEW'][2] = EnumEntry('GOPRO_FIELD_OF_VIEW_NARROW', '''0x02: Narrow''') +GOPRO_FIELD_OF_VIEW_ENUM_END = 3 # +enums['GOPRO_FIELD_OF_VIEW'][3] = EnumEntry('GOPRO_FIELD_OF_VIEW_ENUM_END', '''''') + +# GOPRO_VIDEO_SETTINGS_FLAGS +enums['GOPRO_VIDEO_SETTINGS_FLAGS'] = {} +GOPRO_VIDEO_SETTINGS_TV_MODE = 1 # 0=NTSC, 1=PAL +enums['GOPRO_VIDEO_SETTINGS_FLAGS'][1] = EnumEntry('GOPRO_VIDEO_SETTINGS_TV_MODE', '''0=NTSC, 1=PAL''') +GOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END = 2 # +enums['GOPRO_VIDEO_SETTINGS_FLAGS'][2] = EnumEntry('GOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END', '''''') + +# GOPRO_PHOTO_RESOLUTION +enums['GOPRO_PHOTO_RESOLUTION'] = {} +GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM = 0 # 5MP Medium +enums['GOPRO_PHOTO_RESOLUTION'][0] = EnumEntry('GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM', '''5MP Medium''') +GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM = 1 # 7MP Medium +enums['GOPRO_PHOTO_RESOLUTION'][1] = EnumEntry('GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM', '''7MP Medium''') +GOPRO_PHOTO_RESOLUTION_7MP_WIDE = 2 # 7MP Wide +enums['GOPRO_PHOTO_RESOLUTION'][2] = EnumEntry('GOPRO_PHOTO_RESOLUTION_7MP_WIDE', '''7MP Wide''') +GOPRO_PHOTO_RESOLUTION_10MP_WIDE = 3 # 10MP Wide +enums['GOPRO_PHOTO_RESOLUTION'][3] = EnumEntry('GOPRO_PHOTO_RESOLUTION_10MP_WIDE', '''10MP Wide''') +GOPRO_PHOTO_RESOLUTION_12MP_WIDE = 4 # 12MP Wide +enums['GOPRO_PHOTO_RESOLUTION'][4] = EnumEntry('GOPRO_PHOTO_RESOLUTION_12MP_WIDE', '''12MP Wide''') +GOPRO_PHOTO_RESOLUTION_ENUM_END = 5 # +enums['GOPRO_PHOTO_RESOLUTION'][5] = EnumEntry('GOPRO_PHOTO_RESOLUTION_ENUM_END', '''''') + +# GOPRO_PROTUNE_WHITE_BALANCE +enums['GOPRO_PROTUNE_WHITE_BALANCE'] = {} +GOPRO_PROTUNE_WHITE_BALANCE_AUTO = 0 # Auto +enums['GOPRO_PROTUNE_WHITE_BALANCE'][0] = EnumEntry('GOPRO_PROTUNE_WHITE_BALANCE_AUTO', '''Auto''') +GOPRO_PROTUNE_WHITE_BALANCE_3000K = 1 # 3000K +enums['GOPRO_PROTUNE_WHITE_BALANCE'][1] = EnumEntry('GOPRO_PROTUNE_WHITE_BALANCE_3000K', '''3000K''') +GOPRO_PROTUNE_WHITE_BALANCE_5500K = 2 # 5500K +enums['GOPRO_PROTUNE_WHITE_BALANCE'][2] = EnumEntry('GOPRO_PROTUNE_WHITE_BALANCE_5500K', '''5500K''') +GOPRO_PROTUNE_WHITE_BALANCE_6500K = 3 # 6500K +enums['GOPRO_PROTUNE_WHITE_BALANCE'][3] = EnumEntry('GOPRO_PROTUNE_WHITE_BALANCE_6500K', '''6500K''') +GOPRO_PROTUNE_WHITE_BALANCE_RAW = 4 # Camera Raw +enums['GOPRO_PROTUNE_WHITE_BALANCE'][4] = EnumEntry('GOPRO_PROTUNE_WHITE_BALANCE_RAW', '''Camera Raw''') +GOPRO_PROTUNE_WHITE_BALANCE_ENUM_END = 5 # +enums['GOPRO_PROTUNE_WHITE_BALANCE'][5] = EnumEntry('GOPRO_PROTUNE_WHITE_BALANCE_ENUM_END', '''''') + +# GOPRO_PROTUNE_COLOUR +enums['GOPRO_PROTUNE_COLOUR'] = {} +GOPRO_PROTUNE_COLOUR_STANDARD = 0 # Auto +enums['GOPRO_PROTUNE_COLOUR'][0] = EnumEntry('GOPRO_PROTUNE_COLOUR_STANDARD', '''Auto''') +GOPRO_PROTUNE_COLOUR_NEUTRAL = 1 # Neutral +enums['GOPRO_PROTUNE_COLOUR'][1] = EnumEntry('GOPRO_PROTUNE_COLOUR_NEUTRAL', '''Neutral''') +GOPRO_PROTUNE_COLOUR_ENUM_END = 2 # +enums['GOPRO_PROTUNE_COLOUR'][2] = EnumEntry('GOPRO_PROTUNE_COLOUR_ENUM_END', '''''') + +# GOPRO_PROTUNE_GAIN +enums['GOPRO_PROTUNE_GAIN'] = {} +GOPRO_PROTUNE_GAIN_400 = 0 # ISO 400 +enums['GOPRO_PROTUNE_GAIN'][0] = EnumEntry('GOPRO_PROTUNE_GAIN_400', '''ISO 400''') +GOPRO_PROTUNE_GAIN_800 = 1 # ISO 800 (Only Hero 4) +enums['GOPRO_PROTUNE_GAIN'][1] = EnumEntry('GOPRO_PROTUNE_GAIN_800', '''ISO 800 (Only Hero 4)''') +GOPRO_PROTUNE_GAIN_1600 = 2 # ISO 1600 +enums['GOPRO_PROTUNE_GAIN'][2] = EnumEntry('GOPRO_PROTUNE_GAIN_1600', '''ISO 1600''') +GOPRO_PROTUNE_GAIN_3200 = 3 # ISO 3200 (Only Hero 4) +enums['GOPRO_PROTUNE_GAIN'][3] = EnumEntry('GOPRO_PROTUNE_GAIN_3200', '''ISO 3200 (Only Hero 4)''') +GOPRO_PROTUNE_GAIN_6400 = 4 # ISO 6400 +enums['GOPRO_PROTUNE_GAIN'][4] = EnumEntry('GOPRO_PROTUNE_GAIN_6400', '''ISO 6400''') +GOPRO_PROTUNE_GAIN_ENUM_END = 5 # +enums['GOPRO_PROTUNE_GAIN'][5] = EnumEntry('GOPRO_PROTUNE_GAIN_ENUM_END', '''''') + +# GOPRO_PROTUNE_SHARPNESS +enums['GOPRO_PROTUNE_SHARPNESS'] = {} +GOPRO_PROTUNE_SHARPNESS_LOW = 0 # Low Sharpness +enums['GOPRO_PROTUNE_SHARPNESS'][0] = EnumEntry('GOPRO_PROTUNE_SHARPNESS_LOW', '''Low Sharpness''') +GOPRO_PROTUNE_SHARPNESS_MEDIUM = 1 # Medium Sharpness +enums['GOPRO_PROTUNE_SHARPNESS'][1] = EnumEntry('GOPRO_PROTUNE_SHARPNESS_MEDIUM', '''Medium Sharpness''') +GOPRO_PROTUNE_SHARPNESS_HIGH = 2 # High Sharpness +enums['GOPRO_PROTUNE_SHARPNESS'][2] = EnumEntry('GOPRO_PROTUNE_SHARPNESS_HIGH', '''High Sharpness''') +GOPRO_PROTUNE_SHARPNESS_ENUM_END = 3 # +enums['GOPRO_PROTUNE_SHARPNESS'][3] = EnumEntry('GOPRO_PROTUNE_SHARPNESS_ENUM_END', '''''') + +# GOPRO_PROTUNE_EXPOSURE +enums['GOPRO_PROTUNE_EXPOSURE'] = {} +GOPRO_PROTUNE_EXPOSURE_NEG_5_0 = 0 # -5.0 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][0] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_5_0', '''-5.0 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_NEG_4_5 = 1 # -4.5 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][1] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_4_5', '''-4.5 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_NEG_4_0 = 2 # -4.0 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][2] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_4_0', '''-4.0 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_NEG_3_5 = 3 # -3.5 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][3] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_3_5', '''-3.5 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_NEG_3_0 = 4 # -3.0 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][4] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_3_0', '''-3.0 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_NEG_2_5 = 5 # -2.5 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][5] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_2_5', '''-2.5 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_NEG_2_0 = 6 # -2.0 EV +enums['GOPRO_PROTUNE_EXPOSURE'][6] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_2_0', '''-2.0 EV''') +GOPRO_PROTUNE_EXPOSURE_NEG_1_5 = 7 # -1.5 EV +enums['GOPRO_PROTUNE_EXPOSURE'][7] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_1_5', '''-1.5 EV''') +GOPRO_PROTUNE_EXPOSURE_NEG_1_0 = 8 # -1.0 EV +enums['GOPRO_PROTUNE_EXPOSURE'][8] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_1_0', '''-1.0 EV''') +GOPRO_PROTUNE_EXPOSURE_NEG_0_5 = 9 # -0.5 EV +enums['GOPRO_PROTUNE_EXPOSURE'][9] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_NEG_0_5', '''-0.5 EV''') +GOPRO_PROTUNE_EXPOSURE_ZERO = 10 # 0.0 EV +enums['GOPRO_PROTUNE_EXPOSURE'][10] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_ZERO', '''0.0 EV''') +GOPRO_PROTUNE_EXPOSURE_POS_0_5 = 11 # +0.5 EV +enums['GOPRO_PROTUNE_EXPOSURE'][11] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_0_5', '''+0.5 EV''') +GOPRO_PROTUNE_EXPOSURE_POS_1_0 = 12 # +1.0 EV +enums['GOPRO_PROTUNE_EXPOSURE'][12] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_1_0', '''+1.0 EV''') +GOPRO_PROTUNE_EXPOSURE_POS_1_5 = 13 # +1.5 EV +enums['GOPRO_PROTUNE_EXPOSURE'][13] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_1_5', '''+1.5 EV''') +GOPRO_PROTUNE_EXPOSURE_POS_2_0 = 14 # +2.0 EV +enums['GOPRO_PROTUNE_EXPOSURE'][14] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_2_0', '''+2.0 EV''') +GOPRO_PROTUNE_EXPOSURE_POS_2_5 = 15 # +2.5 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][15] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_2_5', '''+2.5 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_POS_3_0 = 16 # +3.0 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][16] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_3_0', '''+3.0 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_POS_3_5 = 17 # +3.5 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][17] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_3_5', '''+3.5 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_POS_4_0 = 18 # +4.0 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][18] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_4_0', '''+4.0 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_POS_4_5 = 19 # +4.5 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][19] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_4_5', '''+4.5 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_POS_5_0 = 20 # +5.0 EV (Hero 3+ Only) +enums['GOPRO_PROTUNE_EXPOSURE'][20] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_POS_5_0', '''+5.0 EV (Hero 3+ Only)''') +GOPRO_PROTUNE_EXPOSURE_ENUM_END = 21 # +enums['GOPRO_PROTUNE_EXPOSURE'][21] = EnumEntry('GOPRO_PROTUNE_EXPOSURE_ENUM_END', '''''') + +# GOPRO_CHARGING +enums['GOPRO_CHARGING'] = {} +GOPRO_CHARGING_DISABLED = 0 # Charging disabled +enums['GOPRO_CHARGING'][0] = EnumEntry('GOPRO_CHARGING_DISABLED', '''Charging disabled''') +GOPRO_CHARGING_ENABLED = 1 # Charging enabled +enums['GOPRO_CHARGING'][1] = EnumEntry('GOPRO_CHARGING_ENABLED', '''Charging enabled''') +GOPRO_CHARGING_ENUM_END = 2 # +enums['GOPRO_CHARGING'][2] = EnumEntry('GOPRO_CHARGING_ENUM_END', '''''') + +# GOPRO_MODEL +enums['GOPRO_MODEL'] = {} +GOPRO_MODEL_UNKNOWN = 0 # Unknown gopro model +enums['GOPRO_MODEL'][0] = EnumEntry('GOPRO_MODEL_UNKNOWN', '''Unknown gopro model''') +GOPRO_MODEL_HERO_3_PLUS_SILVER = 1 # Hero 3+ Silver (HeroBus not supported by GoPro) +enums['GOPRO_MODEL'][1] = EnumEntry('GOPRO_MODEL_HERO_3_PLUS_SILVER', '''Hero 3+ Silver (HeroBus not supported by GoPro)''') +GOPRO_MODEL_HERO_3_PLUS_BLACK = 2 # Hero 3+ Black +enums['GOPRO_MODEL'][2] = EnumEntry('GOPRO_MODEL_HERO_3_PLUS_BLACK', '''Hero 3+ Black''') +GOPRO_MODEL_HERO_4_SILVER = 3 # Hero 4 Silver +enums['GOPRO_MODEL'][3] = EnumEntry('GOPRO_MODEL_HERO_4_SILVER', '''Hero 4 Silver''') +GOPRO_MODEL_HERO_4_BLACK = 4 # Hero 4 Black +enums['GOPRO_MODEL'][4] = EnumEntry('GOPRO_MODEL_HERO_4_BLACK', '''Hero 4 Black''') +GOPRO_MODEL_ENUM_END = 5 # +enums['GOPRO_MODEL'][5] = EnumEntry('GOPRO_MODEL_ENUM_END', '''''') + +# GOPRO_BURST_RATE +enums['GOPRO_BURST_RATE'] = {} +GOPRO_BURST_RATE_3_IN_1_SECOND = 0 # 3 Shots / 1 Second +enums['GOPRO_BURST_RATE'][0] = EnumEntry('GOPRO_BURST_RATE_3_IN_1_SECOND', '''3 Shots / 1 Second''') +GOPRO_BURST_RATE_5_IN_1_SECOND = 1 # 5 Shots / 1 Second +enums['GOPRO_BURST_RATE'][1] = EnumEntry('GOPRO_BURST_RATE_5_IN_1_SECOND', '''5 Shots / 1 Second''') +GOPRO_BURST_RATE_10_IN_1_SECOND = 2 # 10 Shots / 1 Second +enums['GOPRO_BURST_RATE'][2] = EnumEntry('GOPRO_BURST_RATE_10_IN_1_SECOND', '''10 Shots / 1 Second''') +GOPRO_BURST_RATE_10_IN_2_SECOND = 3 # 10 Shots / 2 Second +enums['GOPRO_BURST_RATE'][3] = EnumEntry('GOPRO_BURST_RATE_10_IN_2_SECOND', '''10 Shots / 2 Second''') +GOPRO_BURST_RATE_10_IN_3_SECOND = 4 # 10 Shots / 3 Second (Hero 4 Only) +enums['GOPRO_BURST_RATE'][4] = EnumEntry('GOPRO_BURST_RATE_10_IN_3_SECOND', '''10 Shots / 3 Second (Hero 4 Only)''') +GOPRO_BURST_RATE_30_IN_1_SECOND = 5 # 30 Shots / 1 Second +enums['GOPRO_BURST_RATE'][5] = EnumEntry('GOPRO_BURST_RATE_30_IN_1_SECOND', '''30 Shots / 1 Second''') +GOPRO_BURST_RATE_30_IN_2_SECOND = 6 # 30 Shots / 2 Second +enums['GOPRO_BURST_RATE'][6] = EnumEntry('GOPRO_BURST_RATE_30_IN_2_SECOND', '''30 Shots / 2 Second''') +GOPRO_BURST_RATE_30_IN_3_SECOND = 7 # 30 Shots / 3 Second +enums['GOPRO_BURST_RATE'][7] = EnumEntry('GOPRO_BURST_RATE_30_IN_3_SECOND', '''30 Shots / 3 Second''') +GOPRO_BURST_RATE_30_IN_6_SECOND = 8 # 30 Shots / 6 Second +enums['GOPRO_BURST_RATE'][8] = EnumEntry('GOPRO_BURST_RATE_30_IN_6_SECOND', '''30 Shots / 6 Second''') +GOPRO_BURST_RATE_ENUM_END = 9 # +enums['GOPRO_BURST_RATE'][9] = EnumEntry('GOPRO_BURST_RATE_ENUM_END', '''''') + +# LED_CONTROL_PATTERN +enums['LED_CONTROL_PATTERN'] = {} +LED_CONTROL_PATTERN_OFF = 0 # LED patterns off (return control to regular vehicle control) +enums['LED_CONTROL_PATTERN'][0] = EnumEntry('LED_CONTROL_PATTERN_OFF', '''LED patterns off (return control to regular vehicle control)''') +LED_CONTROL_PATTERN_FIRMWAREUPDATE = 1 # LEDs show pattern during firmware update +enums['LED_CONTROL_PATTERN'][1] = EnumEntry('LED_CONTROL_PATTERN_FIRMWAREUPDATE', '''LEDs show pattern during firmware update''') +LED_CONTROL_PATTERN_CUSTOM = 255 # Custom Pattern using custom bytes fields +enums['LED_CONTROL_PATTERN'][255] = EnumEntry('LED_CONTROL_PATTERN_CUSTOM', '''Custom Pattern using custom bytes fields''') +LED_CONTROL_PATTERN_ENUM_END = 256 # +enums['LED_CONTROL_PATTERN'][256] = EnumEntry('LED_CONTROL_PATTERN_ENUM_END', '''''') + +# EKF_STATUS_FLAGS +enums['EKF_STATUS_FLAGS'] = {} +EKF_ATTITUDE = 1 # set if EKF's attitude estimate is good +enums['EKF_STATUS_FLAGS'][1] = EnumEntry('EKF_ATTITUDE', '''set if EKF's attitude estimate is good''') +EKF_VELOCITY_HORIZ = 2 # set if EKF's horizontal velocity estimate is good +enums['EKF_STATUS_FLAGS'][2] = EnumEntry('EKF_VELOCITY_HORIZ', '''set if EKF's horizontal velocity estimate is good''') +EKF_VELOCITY_VERT = 4 # set if EKF's vertical velocity estimate is good +enums['EKF_STATUS_FLAGS'][4] = EnumEntry('EKF_VELOCITY_VERT', '''set if EKF's vertical velocity estimate is good''') +EKF_POS_HORIZ_REL = 8 # set if EKF's horizontal position (relative) estimate is good +enums['EKF_STATUS_FLAGS'][8] = EnumEntry('EKF_POS_HORIZ_REL', '''set if EKF's horizontal position (relative) estimate is good''') +EKF_POS_HORIZ_ABS = 16 # set if EKF's horizontal position (absolute) estimate is good +enums['EKF_STATUS_FLAGS'][16] = EnumEntry('EKF_POS_HORIZ_ABS', '''set if EKF's horizontal position (absolute) estimate is good''') +EKF_POS_VERT_ABS = 32 # set if EKF's vertical position (absolute) estimate is good +enums['EKF_STATUS_FLAGS'][32] = EnumEntry('EKF_POS_VERT_ABS', '''set if EKF's vertical position (absolute) estimate is good''') +EKF_POS_VERT_AGL = 64 # set if EKF's vertical position (above ground) estimate is good +enums['EKF_STATUS_FLAGS'][64] = EnumEntry('EKF_POS_VERT_AGL', '''set if EKF's vertical position (above ground) estimate is good''') +EKF_CONST_POS_MODE = 128 # EKF is in constant position mode and does not know it's absolute or + # relative position +enums['EKF_STATUS_FLAGS'][128] = EnumEntry('EKF_CONST_POS_MODE', '''EKF is in constant position mode and does not know it's absolute or relative position''') +EKF_PRED_POS_HORIZ_REL = 256 # set if EKF's predicted horizontal position (relative) estimate is good +enums['EKF_STATUS_FLAGS'][256] = EnumEntry('EKF_PRED_POS_HORIZ_REL', '''set if EKF's predicted horizontal position (relative) estimate is good''') +EKF_PRED_POS_HORIZ_ABS = 512 # set if EKF's predicted horizontal position (absolute) estimate is good +enums['EKF_STATUS_FLAGS'][512] = EnumEntry('EKF_PRED_POS_HORIZ_ABS', '''set if EKF's predicted horizontal position (absolute) estimate is good''') +EKF_STATUS_FLAGS_ENUM_END = 513 # +enums['EKF_STATUS_FLAGS'][513] = EnumEntry('EKF_STATUS_FLAGS_ENUM_END', '''''') + +# PID_TUNING_AXIS +enums['PID_TUNING_AXIS'] = {} +PID_TUNING_ROLL = 1 # +enums['PID_TUNING_AXIS'][1] = EnumEntry('PID_TUNING_ROLL', '''''') +PID_TUNING_PITCH = 2 # +enums['PID_TUNING_AXIS'][2] = EnumEntry('PID_TUNING_PITCH', '''''') +PID_TUNING_YAW = 3 # +enums['PID_TUNING_AXIS'][3] = EnumEntry('PID_TUNING_YAW', '''''') +PID_TUNING_ACCZ = 4 # +enums['PID_TUNING_AXIS'][4] = EnumEntry('PID_TUNING_ACCZ', '''''') +PID_TUNING_STEER = 5 # +enums['PID_TUNING_AXIS'][5] = EnumEntry('PID_TUNING_STEER', '''''') +PID_TUNING_AXIS_ENUM_END = 6 # +enums['PID_TUNING_AXIS'][6] = EnumEntry('PID_TUNING_AXIS_ENUM_END', '''''') + +# MAG_CAL_STATUS +enums['MAG_CAL_STATUS'] = {} +MAG_CAL_NOT_STARTED = 0 # +enums['MAG_CAL_STATUS'][0] = EnumEntry('MAG_CAL_NOT_STARTED', '''''') +MAG_CAL_WAITING_TO_START = 1 # +enums['MAG_CAL_STATUS'][1] = EnumEntry('MAG_CAL_WAITING_TO_START', '''''') +MAG_CAL_RUNNING_STEP_ONE = 2 # +enums['MAG_CAL_STATUS'][2] = EnumEntry('MAG_CAL_RUNNING_STEP_ONE', '''''') +MAG_CAL_RUNNING_STEP_TWO = 3 # +enums['MAG_CAL_STATUS'][3] = EnumEntry('MAG_CAL_RUNNING_STEP_TWO', '''''') +MAG_CAL_SUCCESS = 4 # +enums['MAG_CAL_STATUS'][4] = EnumEntry('MAG_CAL_SUCCESS', '''''') +MAG_CAL_FAILED = 5 # +enums['MAG_CAL_STATUS'][5] = EnumEntry('MAG_CAL_FAILED', '''''') +MAG_CAL_STATUS_ENUM_END = 6 # +enums['MAG_CAL_STATUS'][6] = EnumEntry('MAG_CAL_STATUS_ENUM_END', '''''') + +# MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS +enums['MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS'] = {} +MAV_REMOTE_LOG_DATA_BLOCK_STOP = 2147483645 # UAV to stop sending DataFlash blocks +enums['MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS'][2147483645] = EnumEntry('MAV_REMOTE_LOG_DATA_BLOCK_STOP', '''UAV to stop sending DataFlash blocks''') +MAV_REMOTE_LOG_DATA_BLOCK_START = 2147483646 # UAV to start sending DataFlash blocks +enums['MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS'][2147483646] = EnumEntry('MAV_REMOTE_LOG_DATA_BLOCK_START', '''UAV to start sending DataFlash blocks''') +MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS_ENUM_END = 2147483647 # +enums['MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS'][2147483647] = EnumEntry('MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS_ENUM_END', '''''') + +# MAV_REMOTE_LOG_DATA_BLOCK_STATUSES +enums['MAV_REMOTE_LOG_DATA_BLOCK_STATUSES'] = {} +MAV_REMOTE_LOG_DATA_BLOCK_NACK = 0 # This block has NOT been received +enums['MAV_REMOTE_LOG_DATA_BLOCK_STATUSES'][0] = EnumEntry('MAV_REMOTE_LOG_DATA_BLOCK_NACK', '''This block has NOT been received''') +MAV_REMOTE_LOG_DATA_BLOCK_ACK = 1 # This block has been received +enums['MAV_REMOTE_LOG_DATA_BLOCK_STATUSES'][1] = EnumEntry('MAV_REMOTE_LOG_DATA_BLOCK_ACK', '''This block has been received''') +MAV_REMOTE_LOG_DATA_BLOCK_STATUSES_ENUM_END = 2 # +enums['MAV_REMOTE_LOG_DATA_BLOCK_STATUSES'][2] = EnumEntry('MAV_REMOTE_LOG_DATA_BLOCK_STATUSES_ENUM_END', '''''') + +# MAV_AUTOPILOT +enums['MAV_AUTOPILOT'] = {} +MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything +enums['MAV_AUTOPILOT'][0] = EnumEntry('MAV_AUTOPILOT_GENERIC', '''Generic autopilot, full support for everything''') +MAV_AUTOPILOT_RESERVED = 1 # Reserved for future use. +enums['MAV_AUTOPILOT'][1] = EnumEntry('MAV_AUTOPILOT_RESERVED', '''Reserved for future use.''') +MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu +enums['MAV_AUTOPILOT'][2] = EnumEntry('MAV_AUTOPILOT_SLUGS', '''SLUGS autopilot, http://slugsuav.soe.ucsc.edu''') +MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com +enums['MAV_AUTOPILOT'][3] = EnumEntry('MAV_AUTOPILOT_ARDUPILOTMEGA', '''ArduPilotMega / ArduCopter, http://diydrones.com''') +MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org +enums['MAV_AUTOPILOT'][4] = EnumEntry('MAV_AUTOPILOT_OPENPILOT', '''OpenPilot, http://openpilot.org''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints +enums['MAV_AUTOPILOT'][5] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY', '''Generic autopilot only supporting simple waypoints''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation + # commands +enums['MAV_AUTOPILOT'][6] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY', '''Generic autopilot supporting waypoints and other simple navigation commands''') +MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set +enums['MAV_AUTOPILOT'][7] = EnumEntry('MAV_AUTOPILOT_GENERIC_MISSION_FULL', '''Generic autopilot supporting the full mission command set''') +MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component +enums['MAV_AUTOPILOT'][8] = EnumEntry('MAV_AUTOPILOT_INVALID', '''No valid autopilot, e.g. a GCS or other MAVLink component''') +MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi +enums['MAV_AUTOPILOT'][9] = EnumEntry('MAV_AUTOPILOT_PPZ', '''PPZ UAV - http://nongnu.org/paparazzi''') +MAV_AUTOPILOT_UDB = 10 # UAV Dev Board +enums['MAV_AUTOPILOT'][10] = EnumEntry('MAV_AUTOPILOT_UDB', '''UAV Dev Board''') +MAV_AUTOPILOT_FP = 11 # FlexiPilot +enums['MAV_AUTOPILOT'][11] = EnumEntry('MAV_AUTOPILOT_FP', '''FlexiPilot''') +MAV_AUTOPILOT_PX4 = 12 # PX4 Autopilot - http://pixhawk.ethz.ch/px4/ +enums['MAV_AUTOPILOT'][12] = EnumEntry('MAV_AUTOPILOT_PX4', '''PX4 Autopilot - http://pixhawk.ethz.ch/px4/''') +MAV_AUTOPILOT_SMACCMPILOT = 13 # SMACCMPilot - http://smaccmpilot.org +enums['MAV_AUTOPILOT'][13] = EnumEntry('MAV_AUTOPILOT_SMACCMPILOT', '''SMACCMPilot - http://smaccmpilot.org''') +MAV_AUTOPILOT_AUTOQUAD = 14 # AutoQuad -- http://autoquad.org +enums['MAV_AUTOPILOT'][14] = EnumEntry('MAV_AUTOPILOT_AUTOQUAD', '''AutoQuad -- http://autoquad.org''') +MAV_AUTOPILOT_ARMAZILA = 15 # Armazila -- http://armazila.com +enums['MAV_AUTOPILOT'][15] = EnumEntry('MAV_AUTOPILOT_ARMAZILA', '''Armazila -- http://armazila.com''') +MAV_AUTOPILOT_AEROB = 16 # Aerob -- http://aerob.ru +enums['MAV_AUTOPILOT'][16] = EnumEntry('MAV_AUTOPILOT_AEROB', '''Aerob -- http://aerob.ru''') +MAV_AUTOPILOT_ASLUAV = 17 # ASLUAV autopilot -- http://www.asl.ethz.ch +enums['MAV_AUTOPILOT'][17] = EnumEntry('MAV_AUTOPILOT_ASLUAV', '''ASLUAV autopilot -- http://www.asl.ethz.ch''') +MAV_AUTOPILOT_ENUM_END = 18 # +enums['MAV_AUTOPILOT'][18] = EnumEntry('MAV_AUTOPILOT_ENUM_END', '''''') + +# MAV_TYPE +enums['MAV_TYPE'] = {} +MAV_TYPE_GENERIC = 0 # Generic micro air vehicle. +enums['MAV_TYPE'][0] = EnumEntry('MAV_TYPE_GENERIC', '''Generic micro air vehicle.''') +MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft. +enums['MAV_TYPE'][1] = EnumEntry('MAV_TYPE_FIXED_WING', '''Fixed wing aircraft.''') +MAV_TYPE_QUADROTOR = 2 # Quadrotor +enums['MAV_TYPE'][2] = EnumEntry('MAV_TYPE_QUADROTOR', '''Quadrotor''') +MAV_TYPE_COAXIAL = 3 # Coaxial helicopter +enums['MAV_TYPE'][3] = EnumEntry('MAV_TYPE_COAXIAL', '''Coaxial helicopter''') +MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor. +enums['MAV_TYPE'][4] = EnumEntry('MAV_TYPE_HELICOPTER', '''Normal helicopter with tail rotor.''') +MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation +enums['MAV_TYPE'][5] = EnumEntry('MAV_TYPE_ANTENNA_TRACKER', '''Ground installation''') +MAV_TYPE_GCS = 6 # Operator control unit / ground control station +enums['MAV_TYPE'][6] = EnumEntry('MAV_TYPE_GCS', '''Operator control unit / ground control station''') +MAV_TYPE_AIRSHIP = 7 # Airship, controlled +enums['MAV_TYPE'][7] = EnumEntry('MAV_TYPE_AIRSHIP', '''Airship, controlled''') +MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled +enums['MAV_TYPE'][8] = EnumEntry('MAV_TYPE_FREE_BALLOON', '''Free balloon, uncontrolled''') +MAV_TYPE_ROCKET = 9 # Rocket +enums['MAV_TYPE'][9] = EnumEntry('MAV_TYPE_ROCKET', '''Rocket''') +MAV_TYPE_GROUND_ROVER = 10 # Ground rover +enums['MAV_TYPE'][10] = EnumEntry('MAV_TYPE_GROUND_ROVER', '''Ground rover''') +MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship +enums['MAV_TYPE'][11] = EnumEntry('MAV_TYPE_SURFACE_BOAT', '''Surface vessel, boat, ship''') +MAV_TYPE_SUBMARINE = 12 # Submarine +enums['MAV_TYPE'][12] = EnumEntry('MAV_TYPE_SUBMARINE', '''Submarine''') +MAV_TYPE_HEXAROTOR = 13 # Hexarotor +enums['MAV_TYPE'][13] = EnumEntry('MAV_TYPE_HEXAROTOR', '''Hexarotor''') +MAV_TYPE_OCTOROTOR = 14 # Octorotor +enums['MAV_TYPE'][14] = EnumEntry('MAV_TYPE_OCTOROTOR', '''Octorotor''') +MAV_TYPE_TRICOPTER = 15 # Octorotor +enums['MAV_TYPE'][15] = EnumEntry('MAV_TYPE_TRICOPTER', '''Octorotor''') +MAV_TYPE_FLAPPING_WING = 16 # Flapping wing +enums['MAV_TYPE'][16] = EnumEntry('MAV_TYPE_FLAPPING_WING', '''Flapping wing''') +MAV_TYPE_KITE = 17 # Flapping wing +enums['MAV_TYPE'][17] = EnumEntry('MAV_TYPE_KITE', '''Flapping wing''') +MAV_TYPE_ONBOARD_CONTROLLER = 18 # Onboard companion controller +enums['MAV_TYPE'][18] = EnumEntry('MAV_TYPE_ONBOARD_CONTROLLER', '''Onboard companion controller''') +MAV_TYPE_VTOL_DUOROTOR = 19 # Two-rotor VTOL using control surfaces in vertical operation in + # addition. Tailsitter. +enums['MAV_TYPE'][19] = EnumEntry('MAV_TYPE_VTOL_DUOROTOR', '''Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.''') +MAV_TYPE_VTOL_QUADROTOR = 20 # Quad-rotor VTOL using a V-shaped quad config in vertical operation. + # Tailsitter. +enums['MAV_TYPE'][20] = EnumEntry('MAV_TYPE_VTOL_QUADROTOR', '''Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.''') +MAV_TYPE_VTOL_TILTROTOR = 21 # Tiltrotor VTOL +enums['MAV_TYPE'][21] = EnumEntry('MAV_TYPE_VTOL_TILTROTOR', '''Tiltrotor VTOL''') +MAV_TYPE_VTOL_RESERVED2 = 22 # VTOL reserved 2 +enums['MAV_TYPE'][22] = EnumEntry('MAV_TYPE_VTOL_RESERVED2', '''VTOL reserved 2''') +MAV_TYPE_VTOL_RESERVED3 = 23 # VTOL reserved 3 +enums['MAV_TYPE'][23] = EnumEntry('MAV_TYPE_VTOL_RESERVED3', '''VTOL reserved 3''') +MAV_TYPE_VTOL_RESERVED4 = 24 # VTOL reserved 4 +enums['MAV_TYPE'][24] = EnumEntry('MAV_TYPE_VTOL_RESERVED4', '''VTOL reserved 4''') +MAV_TYPE_VTOL_RESERVED5 = 25 # VTOL reserved 5 +enums['MAV_TYPE'][25] = EnumEntry('MAV_TYPE_VTOL_RESERVED5', '''VTOL reserved 5''') +MAV_TYPE_GIMBAL = 26 # Onboard gimbal +enums['MAV_TYPE'][26] = EnumEntry('MAV_TYPE_GIMBAL', '''Onboard gimbal''') +MAV_TYPE_ADSB = 27 # Onboard ADSB peripheral +enums['MAV_TYPE'][27] = EnumEntry('MAV_TYPE_ADSB', '''Onboard ADSB peripheral''') +MAV_TYPE_ENUM_END = 28 # +enums['MAV_TYPE'][28] = EnumEntry('MAV_TYPE_ENUM_END', '''''') + +# FIRMWARE_VERSION_TYPE +enums['FIRMWARE_VERSION_TYPE'] = {} +FIRMWARE_VERSION_TYPE_DEV = 0 # development release +enums['FIRMWARE_VERSION_TYPE'][0] = EnumEntry('FIRMWARE_VERSION_TYPE_DEV', '''development release''') +FIRMWARE_VERSION_TYPE_ALPHA = 64 # alpha release +enums['FIRMWARE_VERSION_TYPE'][64] = EnumEntry('FIRMWARE_VERSION_TYPE_ALPHA', '''alpha release''') +FIRMWARE_VERSION_TYPE_BETA = 128 # beta release +enums['FIRMWARE_VERSION_TYPE'][128] = EnumEntry('FIRMWARE_VERSION_TYPE_BETA', '''beta release''') +FIRMWARE_VERSION_TYPE_RC = 192 # release candidate +enums['FIRMWARE_VERSION_TYPE'][192] = EnumEntry('FIRMWARE_VERSION_TYPE_RC', '''release candidate''') +FIRMWARE_VERSION_TYPE_OFFICIAL = 255 # official stable release +enums['FIRMWARE_VERSION_TYPE'][255] = EnumEntry('FIRMWARE_VERSION_TYPE_OFFICIAL', '''official stable release''') +FIRMWARE_VERSION_TYPE_ENUM_END = 256 # +enums['FIRMWARE_VERSION_TYPE'][256] = EnumEntry('FIRMWARE_VERSION_TYPE_ENUM_END', '''''') + +# MAV_MODE_FLAG +enums['MAV_MODE_FLAG'] = {} +MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use. +enums['MAV_MODE_FLAG'][1] = EnumEntry('MAV_MODE_FLAG_CUSTOM_MODE_ENABLED', '''0b00000001 Reserved for future use.''') +MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for + # temporary system tests and should not be + # used for stable implementations. +enums['MAV_MODE_FLAG'][2] = EnumEntry('MAV_MODE_FLAG_TEST_ENABLED', '''0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.''') +MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal + # positions. Guided flag can be set or not, + # depends on the actual implementation. +enums['MAV_MODE_FLAG'][4] = EnumEntry('MAV_MODE_FLAG_AUTO_ENABLED', '''0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.''') +MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items. +enums['MAV_MODE_FLAG'][8] = EnumEntry('MAV_MODE_FLAG_GUIDED_ENABLED', '''0b00001000 guided mode enabled, system flies MISSIONs / mission items.''') +MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and + # optionally position). It needs however + # further control inputs to move around. +enums['MAV_MODE_FLAG'][16] = EnumEntry('MAV_MODE_FLAG_STABILIZE_ENABLED', '''0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.''') +MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are + # blocked, but internal software is full + # operational. +enums['MAV_MODE_FLAG'][32] = EnumEntry('MAV_MODE_FLAG_HIL_ENABLED', '''0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.''') +MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled. +enums['MAV_MODE_FLAG'][64] = EnumEntry('MAV_MODE_FLAG_MANUAL_INPUT_ENABLED', '''0b01000000 remote control input is enabled.''') +MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can + # start. Ready to fly. +enums['MAV_MODE_FLAG'][128] = EnumEntry('MAV_MODE_FLAG_SAFETY_ARMED', '''0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.''') +MAV_MODE_FLAG_ENUM_END = 129 # +enums['MAV_MODE_FLAG'][129] = EnumEntry('MAV_MODE_FLAG_ENUM_END', '''''') + +# MAV_MODE_FLAG_DECODE_POSITION +enums['MAV_MODE_FLAG_DECODE_POSITION'] = {} +MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001 +enums['MAV_MODE_FLAG_DECODE_POSITION'][1] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE', '''Eighth bit: 00000001''') +MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010 +enums['MAV_MODE_FLAG_DECODE_POSITION'][2] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_TEST', '''Seventh bit: 00000010''') +MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100 +enums['MAV_MODE_FLAG_DECODE_POSITION'][4] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_AUTO', '''Sixt bit: 00000100''') +MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][8] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_GUIDED', '''Fifth bit: 00001000''') +MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][16] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_STABILIZE', '''Fourth bit: 00010000''') +MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][32] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_HIL', '''Third bit: 00100000''') +MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][64] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_MANUAL', '''Second bit: 01000000''') +MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][128] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_SAFETY', '''First bit: 10000000''') +MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 # +enums['MAV_MODE_FLAG_DECODE_POSITION'][129] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_ENUM_END', '''''') + +# MAV_GOTO +enums['MAV_GOTO'] = {} +MAV_GOTO_DO_HOLD = 0 # Hold at the current position. +enums['MAV_GOTO'][0] = EnumEntry('MAV_GOTO_DO_HOLD', '''Hold at the current position.''') +MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution. +enums['MAV_GOTO'][1] = EnumEntry('MAV_GOTO_DO_CONTINUE', '''Continue with the next item in mission execution.''') +MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system +enums['MAV_GOTO'][2] = EnumEntry('MAV_GOTO_HOLD_AT_CURRENT_POSITION', '''Hold at the current position of the system''') +MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action +enums['MAV_GOTO'][3] = EnumEntry('MAV_GOTO_HOLD_AT_SPECIFIED_POSITION', '''Hold at the position specified in the parameters of the DO_HOLD action''') +MAV_GOTO_ENUM_END = 4 # +enums['MAV_GOTO'][4] = EnumEntry('MAV_GOTO_ENUM_END', '''''') + +# MAV_MODE +enums['MAV_MODE'] = {} +MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set. +enums['MAV_MODE'][0] = EnumEntry('MAV_MODE_PREFLIGHT', '''System is not ready to fly, booting, calibrating, etc. No flag is set.''') +MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][64] = EnumEntry('MAV_MODE_MANUAL_DISARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][66] = EnumEntry('MAV_MODE_TEST_DISARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][80] = EnumEntry('MAV_MODE_STABILIZE_DISARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][88] = EnumEntry('MAV_MODE_GUIDED_DISARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][92] = EnumEntry('MAV_MODE_AUTO_DISARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][192] = EnumEntry('MAV_MODE_MANUAL_ARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][194] = EnumEntry('MAV_MODE_TEST_ARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][208] = EnumEntry('MAV_MODE_STABILIZE_ARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][216] = EnumEntry('MAV_MODE_GUIDED_ARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][220] = EnumEntry('MAV_MODE_AUTO_ARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_ENUM_END = 221 # +enums['MAV_MODE'][221] = EnumEntry('MAV_MODE_ENUM_END', '''''') + +# MAV_STATE +enums['MAV_STATE'] = {} +MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown. +enums['MAV_STATE'][0] = EnumEntry('MAV_STATE_UNINIT', '''Uninitialized system, state is unknown.''') +MAV_STATE_BOOT = 1 # System is booting up. +enums['MAV_STATE'][1] = EnumEntry('MAV_STATE_BOOT', '''System is booting up.''') +MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready. +enums['MAV_STATE'][2] = EnumEntry('MAV_STATE_CALIBRATING', '''System is calibrating and not flight-ready.''') +MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time. +enums['MAV_STATE'][3] = EnumEntry('MAV_STATE_STANDBY', '''System is grounded and on standby. It can be launched any time.''') +MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged. +enums['MAV_STATE'][4] = EnumEntry('MAV_STATE_ACTIVE', '''System is active and might be already airborne. Motors are engaged.''') +MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate. +enums['MAV_STATE'][5] = EnumEntry('MAV_STATE_CRITICAL', '''System is in a non-normal flight mode. It can however still navigate.''') +MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or + # over the whole airframe. It is in mayday and + # going down. +enums['MAV_STATE'][6] = EnumEntry('MAV_STATE_EMERGENCY', '''System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.''') +MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now. +enums['MAV_STATE'][7] = EnumEntry('MAV_STATE_POWEROFF', '''System just initialized its power-down sequence, will shut down now.''') +MAV_STATE_ENUM_END = 8 # +enums['MAV_STATE'][8] = EnumEntry('MAV_STATE_ENUM_END', '''''') + +# MAV_COMPONENT +enums['MAV_COMPONENT'] = {} +MAV_COMP_ID_ALL = 0 # +enums['MAV_COMPONENT'][0] = EnumEntry('MAV_COMP_ID_ALL', '''''') +MAV_COMP_ID_CAMERA = 100 # +enums['MAV_COMPONENT'][100] = EnumEntry('MAV_COMP_ID_CAMERA', '''''') +MAV_COMP_ID_SERVO1 = 140 # +enums['MAV_COMPONENT'][140] = EnumEntry('MAV_COMP_ID_SERVO1', '''''') +MAV_COMP_ID_SERVO2 = 141 # +enums['MAV_COMPONENT'][141] = EnumEntry('MAV_COMP_ID_SERVO2', '''''') +MAV_COMP_ID_SERVO3 = 142 # +enums['MAV_COMPONENT'][142] = EnumEntry('MAV_COMP_ID_SERVO3', '''''') +MAV_COMP_ID_SERVO4 = 143 # +enums['MAV_COMPONENT'][143] = EnumEntry('MAV_COMP_ID_SERVO4', '''''') +MAV_COMP_ID_SERVO5 = 144 # +enums['MAV_COMPONENT'][144] = EnumEntry('MAV_COMP_ID_SERVO5', '''''') +MAV_COMP_ID_SERVO6 = 145 # +enums['MAV_COMPONENT'][145] = EnumEntry('MAV_COMP_ID_SERVO6', '''''') +MAV_COMP_ID_SERVO7 = 146 # +enums['MAV_COMPONENT'][146] = EnumEntry('MAV_COMP_ID_SERVO7', '''''') +MAV_COMP_ID_SERVO8 = 147 # +enums['MAV_COMPONENT'][147] = EnumEntry('MAV_COMP_ID_SERVO8', '''''') +MAV_COMP_ID_SERVO9 = 148 # +enums['MAV_COMPONENT'][148] = EnumEntry('MAV_COMP_ID_SERVO9', '''''') +MAV_COMP_ID_SERVO10 = 149 # +enums['MAV_COMPONENT'][149] = EnumEntry('MAV_COMP_ID_SERVO10', '''''') +MAV_COMP_ID_SERVO11 = 150 # +enums['MAV_COMPONENT'][150] = EnumEntry('MAV_COMP_ID_SERVO11', '''''') +MAV_COMP_ID_SERVO12 = 151 # +enums['MAV_COMPONENT'][151] = EnumEntry('MAV_COMP_ID_SERVO12', '''''') +MAV_COMP_ID_SERVO13 = 152 # +enums['MAV_COMPONENT'][152] = EnumEntry('MAV_COMP_ID_SERVO13', '''''') +MAV_COMP_ID_SERVO14 = 153 # +enums['MAV_COMPONENT'][153] = EnumEntry('MAV_COMP_ID_SERVO14', '''''') +MAV_COMP_ID_GIMBAL = 154 # +enums['MAV_COMPONENT'][154] = EnumEntry('MAV_COMP_ID_GIMBAL', '''''') +MAV_COMP_ID_LOG = 155 # +enums['MAV_COMPONENT'][155] = EnumEntry('MAV_COMP_ID_LOG', '''''') +MAV_COMP_ID_ADSB = 156 # +enums['MAV_COMPONENT'][156] = EnumEntry('MAV_COMP_ID_ADSB', '''''') +MAV_COMP_ID_OSD = 157 # On Screen Display (OSD) devices for video links +enums['MAV_COMPONENT'][157] = EnumEntry('MAV_COMP_ID_OSD', '''On Screen Display (OSD) devices for video links''') +MAV_COMP_ID_PERIPHERAL = 158 # Generic autopilot peripheral component ID. Meant for devices that do + # not implement the parameter sub-protocol +enums['MAV_COMPONENT'][158] = EnumEntry('MAV_COMP_ID_PERIPHERAL', '''Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol''') +MAV_COMP_ID_MAPPER = 180 # +enums['MAV_COMPONENT'][180] = EnumEntry('MAV_COMP_ID_MAPPER', '''''') +MAV_COMP_ID_MISSIONPLANNER = 190 # +enums['MAV_COMPONENT'][190] = EnumEntry('MAV_COMP_ID_MISSIONPLANNER', '''''') +MAV_COMP_ID_PATHPLANNER = 195 # +enums['MAV_COMPONENT'][195] = EnumEntry('MAV_COMP_ID_PATHPLANNER', '''''') +MAV_COMP_ID_IMU = 200 # +enums['MAV_COMPONENT'][200] = EnumEntry('MAV_COMP_ID_IMU', '''''') +MAV_COMP_ID_IMU_2 = 201 # +enums['MAV_COMPONENT'][201] = EnumEntry('MAV_COMP_ID_IMU_2', '''''') +MAV_COMP_ID_IMU_3 = 202 # +enums['MAV_COMPONENT'][202] = EnumEntry('MAV_COMP_ID_IMU_3', '''''') +MAV_COMP_ID_GPS = 220 # +enums['MAV_COMPONENT'][220] = EnumEntry('MAV_COMP_ID_GPS', '''''') +MAV_COMP_ID_UDP_BRIDGE = 240 # +enums['MAV_COMPONENT'][240] = EnumEntry('MAV_COMP_ID_UDP_BRIDGE', '''''') +MAV_COMP_ID_UART_BRIDGE = 241 # +enums['MAV_COMPONENT'][241] = EnumEntry('MAV_COMP_ID_UART_BRIDGE', '''''') +MAV_COMP_ID_SYSTEM_CONTROL = 250 # +enums['MAV_COMPONENT'][250] = EnumEntry('MAV_COMP_ID_SYSTEM_CONTROL', '''''') +MAV_COMPONENT_ENUM_END = 251 # +enums['MAV_COMPONENT'][251] = EnumEntry('MAV_COMPONENT_ENUM_END', '''''') + +# MAV_SYS_STATUS_SENSOR +enums['MAV_SYS_STATUS_SENSOR'] = {} +MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 # 0x01 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][1] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO', '''0x01 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 # 0x02 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][2] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL', '''0x02 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG = 4 # 0x04 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][4] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG', '''0x04 3D magnetometer''') +MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 # 0x08 absolute pressure +enums['MAV_SYS_STATUS_SENSOR'][8] = EnumEntry('MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE', '''0x08 absolute pressure''') +MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 # 0x10 differential pressure +enums['MAV_SYS_STATUS_SENSOR'][16] = EnumEntry('MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE', '''0x10 differential pressure''') +MAV_SYS_STATUS_SENSOR_GPS = 32 # 0x20 GPS +enums['MAV_SYS_STATUS_SENSOR'][32] = EnumEntry('MAV_SYS_STATUS_SENSOR_GPS', '''0x20 GPS''') +MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 # 0x40 optical flow +enums['MAV_SYS_STATUS_SENSOR'][64] = EnumEntry('MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW', '''0x40 optical flow''') +MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 # 0x80 computer vision position +enums['MAV_SYS_STATUS_SENSOR'][128] = EnumEntry('MAV_SYS_STATUS_SENSOR_VISION_POSITION', '''0x80 computer vision position''') +MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 # 0x100 laser based position +enums['MAV_SYS_STATUS_SENSOR'][256] = EnumEntry('MAV_SYS_STATUS_SENSOR_LASER_POSITION', '''0x100 laser based position''') +MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 # 0x200 external ground truth (Vicon or Leica) +enums['MAV_SYS_STATUS_SENSOR'][512] = EnumEntry('MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH', '''0x200 external ground truth (Vicon or Leica)''') +MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 # 0x400 3D angular rate control +enums['MAV_SYS_STATUS_SENSOR'][1024] = EnumEntry('MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL', '''0x400 3D angular rate control''') +MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 # 0x800 attitude stabilization +enums['MAV_SYS_STATUS_SENSOR'][2048] = EnumEntry('MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION', '''0x800 attitude stabilization''') +MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 # 0x1000 yaw position +enums['MAV_SYS_STATUS_SENSOR'][4096] = EnumEntry('MAV_SYS_STATUS_SENSOR_YAW_POSITION', '''0x1000 yaw position''') +MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 # 0x2000 z/altitude control +enums['MAV_SYS_STATUS_SENSOR'][8192] = EnumEntry('MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL', '''0x2000 z/altitude control''') +MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 # 0x4000 x/y position control +enums['MAV_SYS_STATUS_SENSOR'][16384] = EnumEntry('MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL', '''0x4000 x/y position control''') +MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 # 0x8000 motor outputs / control +enums['MAV_SYS_STATUS_SENSOR'][32768] = EnumEntry('MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS', '''0x8000 motor outputs / control''') +MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 # 0x10000 rc receiver +enums['MAV_SYS_STATUS_SENSOR'][65536] = EnumEntry('MAV_SYS_STATUS_SENSOR_RC_RECEIVER', '''0x10000 rc receiver''') +MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 # 0x20000 2nd 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][131072] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO2', '''0x20000 2nd 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 # 0x40000 2nd 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][262144] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL2', '''0x40000 2nd 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 # 0x80000 2nd 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][524288] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG2', '''0x80000 2nd 3D magnetometer''') +MAV_SYS_STATUS_GEOFENCE = 1048576 # 0x100000 geofence +enums['MAV_SYS_STATUS_SENSOR'][1048576] = EnumEntry('MAV_SYS_STATUS_GEOFENCE', '''0x100000 geofence''') +MAV_SYS_STATUS_AHRS = 2097152 # 0x200000 AHRS subsystem health +enums['MAV_SYS_STATUS_SENSOR'][2097152] = EnumEntry('MAV_SYS_STATUS_AHRS', '''0x200000 AHRS subsystem health''') +MAV_SYS_STATUS_TERRAIN = 4194304 # 0x400000 Terrain subsystem health +enums['MAV_SYS_STATUS_SENSOR'][4194304] = EnumEntry('MAV_SYS_STATUS_TERRAIN', '''0x400000 Terrain subsystem health''') +MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 # 0x800000 Motors are reversed +enums['MAV_SYS_STATUS_SENSOR'][8388608] = EnumEntry('MAV_SYS_STATUS_REVERSE_MOTOR', '''0x800000 Motors are reversed''') +MAV_SYS_STATUS_SENSOR_ENUM_END = 8388609 # +enums['MAV_SYS_STATUS_SENSOR'][8388609] = EnumEntry('MAV_SYS_STATUS_SENSOR_ENUM_END', '''''') + +# MAV_FRAME +enums['MAV_FRAME'] = {} +MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude, second value / y: longitude, third + # value / z: positive altitude over mean sea + # level (MSL) +enums['MAV_FRAME'][0] = EnumEntry('MAV_FRAME_GLOBAL', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down). +enums['MAV_FRAME'][1] = EnumEntry('MAV_FRAME_LOCAL_NED', '''Local coordinate frame, Z-up (x: north, y: east, z: down).''') +MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command. +enums['MAV_FRAME'][2] = EnumEntry('MAV_FRAME_MISSION', '''NOT a coordinate frame, indicates a mission command.''') +MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude, second + # value / y: longitude, third value / z: + # positive altitude with 0 being at the + # altitude of the home location. +enums['MAV_FRAME'][3] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up) +enums['MAV_FRAME'][4] = EnumEntry('MAV_FRAME_LOCAL_ENU', '''Local coordinate frame, Z-down (x: east, y: north, z: up)''') +MAV_FRAME_GLOBAL_INT = 5 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude in degrees*1.0e-7, second value / + # y: longitude in degrees*1.0e-7, third value + # / z: positive altitude over mean sea level + # (MSL) +enums['MAV_FRAME'][5] = EnumEntry('MAV_FRAME_GLOBAL_INT', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude with 0 being at the altitude of the + # home location. +enums['MAV_FRAME'][6] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT_INT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame + # should be added to the current local frame + # position. +enums['MAV_FRAME'][7] = EnumEntry('MAV_FRAME_LOCAL_OFFSET_NED', '''Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.''') +MAV_FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control + # is externalized - e.g. useful to command 2 + # m/s^2 acceleration to the right. +enums['MAV_FRAME'][8] = EnumEntry('MAV_FRAME_BODY_NED', '''Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.''') +MAV_FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the + # current flight path, to avoid an obstacle - + # e.g. useful to command 2 m/s^2 acceleration + # to the east. +enums['MAV_FRAME'][9] = EnumEntry('MAV_FRAME_BODY_OFFSET_NED', '''Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees, second value / y: longitude in + # degrees, third value / z: positive altitude + # in meters with 0 being at ground level in + # terrain model. +enums['MAV_FRAME'][10] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude in meters with 0 being at ground + # level in terrain model. +enums['MAV_FRAME'][11] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT_INT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_ENUM_END = 12 # +enums['MAV_FRAME'][12] = EnumEntry('MAV_FRAME_ENUM_END', '''''') + +# MAVLINK_DATA_STREAM_TYPE +enums['MAVLINK_DATA_STREAM_TYPE'] = {} +MAVLINK_DATA_STREAM_IMG_JPEG = 1 # +enums['MAVLINK_DATA_STREAM_TYPE'][1] = EnumEntry('MAVLINK_DATA_STREAM_IMG_JPEG', '''''') +MAVLINK_DATA_STREAM_IMG_BMP = 2 # +enums['MAVLINK_DATA_STREAM_TYPE'][2] = EnumEntry('MAVLINK_DATA_STREAM_IMG_BMP', '''''') +MAVLINK_DATA_STREAM_IMG_RAW8U = 3 # +enums['MAVLINK_DATA_STREAM_TYPE'][3] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW8U', '''''') +MAVLINK_DATA_STREAM_IMG_RAW32U = 4 # +enums['MAVLINK_DATA_STREAM_TYPE'][4] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW32U', '''''') +MAVLINK_DATA_STREAM_IMG_PGM = 5 # +enums['MAVLINK_DATA_STREAM_TYPE'][5] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PGM', '''''') +MAVLINK_DATA_STREAM_IMG_PNG = 6 # +enums['MAVLINK_DATA_STREAM_TYPE'][6] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PNG', '''''') +MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 # +enums['MAVLINK_DATA_STREAM_TYPE'][7] = EnumEntry('MAVLINK_DATA_STREAM_TYPE_ENUM_END', '''''') + +# FENCE_ACTION +enums['FENCE_ACTION'] = {} +FENCE_ACTION_NONE = 0 # Disable fenced mode +enums['FENCE_ACTION'][0] = EnumEntry('FENCE_ACTION_NONE', '''Disable fenced mode''') +FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0) +enums['FENCE_ACTION'][1] = EnumEntry('FENCE_ACTION_GUIDED', '''Switched to guided mode to return point (fence point 0)''') +FENCE_ACTION_REPORT = 2 # Report fence breach, but don't take action +enums['FENCE_ACTION'][2] = EnumEntry('FENCE_ACTION_REPORT', '''Report fence breach, but don't take action''') +FENCE_ACTION_GUIDED_THR_PASS = 3 # Switched to guided mode to return point (fence point 0) with manual + # throttle control +enums['FENCE_ACTION'][3] = EnumEntry('FENCE_ACTION_GUIDED_THR_PASS', '''Switched to guided mode to return point (fence point 0) with manual throttle control''') +FENCE_ACTION_ENUM_END = 4 # +enums['FENCE_ACTION'][4] = EnumEntry('FENCE_ACTION_ENUM_END', '''''') + +# FENCE_BREACH +enums['FENCE_BREACH'] = {} +FENCE_BREACH_NONE = 0 # No last fence breach +enums['FENCE_BREACH'][0] = EnumEntry('FENCE_BREACH_NONE', '''No last fence breach''') +FENCE_BREACH_MINALT = 1 # Breached minimum altitude +enums['FENCE_BREACH'][1] = EnumEntry('FENCE_BREACH_MINALT', '''Breached minimum altitude''') +FENCE_BREACH_MAXALT = 2 # Breached maximum altitude +enums['FENCE_BREACH'][2] = EnumEntry('FENCE_BREACH_MAXALT', '''Breached maximum altitude''') +FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary +enums['FENCE_BREACH'][3] = EnumEntry('FENCE_BREACH_BOUNDARY', '''Breached fence boundary''') +FENCE_BREACH_ENUM_END = 4 # +enums['FENCE_BREACH'][4] = EnumEntry('FENCE_BREACH_ENUM_END', '''''') + +# MAV_MOUNT_MODE +enums['MAV_MOUNT_MODE'] = {} +MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permant memory and + # stop stabilization +enums['MAV_MOUNT_MODE'][0] = EnumEntry('MAV_MOUNT_MODE_RETRACT', '''Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization''') +MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +enums['MAV_MOUNT_MODE'][1] = EnumEntry('MAV_MOUNT_MODE_NEUTRAL', '''Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.''') +MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][2] = EnumEntry('MAV_MOUNT_MODE_MAVLINK_TARGETING', '''Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][3] = EnumEntry('MAV_MOUNT_MODE_RC_TARGETING', '''Load neutral position and start RC Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt +enums['MAV_MOUNT_MODE'][4] = EnumEntry('MAV_MOUNT_MODE_GPS_POINT', '''Load neutral position and start to point to Lat,Lon,Alt''') +MAV_MOUNT_MODE_ENUM_END = 5 # +enums['MAV_MOUNT_MODE'][5] = EnumEntry('MAV_MOUNT_MODE_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_SENSOR_OFFSETS = 150 +MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151 +MAVLINK_MSG_ID_MEMINFO = 152 +MAVLINK_MSG_ID_AP_ADC = 153 +MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154 +MAVLINK_MSG_ID_DIGICAM_CONTROL = 155 +MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156 +MAVLINK_MSG_ID_MOUNT_CONTROL = 157 +MAVLINK_MSG_ID_MOUNT_STATUS = 158 +MAVLINK_MSG_ID_FENCE_POINT = 160 +MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161 +MAVLINK_MSG_ID_FENCE_STATUS = 162 +MAVLINK_MSG_ID_AHRS = 163 +MAVLINK_MSG_ID_SIMSTATE = 164 +MAVLINK_MSG_ID_HWSTATUS = 165 +MAVLINK_MSG_ID_RADIO = 166 +MAVLINK_MSG_ID_LIMITS_STATUS = 167 +MAVLINK_MSG_ID_WIND = 168 +MAVLINK_MSG_ID_DATA16 = 169 +MAVLINK_MSG_ID_DATA32 = 170 +MAVLINK_MSG_ID_DATA64 = 171 +MAVLINK_MSG_ID_DATA96 = 172 +MAVLINK_MSG_ID_RANGEFINDER = 173 +MAVLINK_MSG_ID_AIRSPEED_AUTOCAL = 174 +MAVLINK_MSG_ID_RALLY_POINT = 175 +MAVLINK_MSG_ID_RALLY_FETCH_POINT = 176 +MAVLINK_MSG_ID_COMPASSMOT_STATUS = 177 +MAVLINK_MSG_ID_AHRS2 = 178 +MAVLINK_MSG_ID_CAMERA_STATUS = 179 +MAVLINK_MSG_ID_CAMERA_FEEDBACK = 180 +MAVLINK_MSG_ID_BATTERY2 = 181 +MAVLINK_MSG_ID_AHRS3 = 182 +MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST = 183 +MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK = 184 +MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS = 185 +MAVLINK_MSG_ID_LED_CONTROL = 186 +MAVLINK_MSG_ID_MAG_CAL_PROGRESS = 191 +MAVLINK_MSG_ID_MAG_CAL_REPORT = 192 +MAVLINK_MSG_ID_EKF_STATUS_REPORT = 193 +MAVLINK_MSG_ID_PID_TUNING = 194 +MAVLINK_MSG_ID_GIMBAL_REPORT = 200 +MAVLINK_MSG_ID_GIMBAL_CONTROL = 201 +MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT = 214 +MAVLINK_MSG_ID_GOPRO_HEARTBEAT = 215 +MAVLINK_MSG_ID_GOPRO_GET_REQUEST = 216 +MAVLINK_MSG_ID_GOPRO_GET_RESPONSE = 217 +MAVLINK_MSG_ID_GOPRO_SET_REQUEST = 218 +MAVLINK_MSG_ID_GOPRO_SET_RESPONSE = 219 +MAVLINK_MSG_ID_RPM = 226 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_sensor_offsets_message(MAVLink_message): + ''' + Offsets and calibrations values for hardware sensors. This + makes it easier to debug the calibration process. + ''' + id = MAVLINK_MSG_ID_SENSOR_OFFSETS + name = 'SENSOR_OFFSETS' + fieldnames = ['mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z', 'mag_declination', 'raw_press', 'raw_temp', 'gyro_cal_x', 'gyro_cal_y', 'gyro_cal_z', 'accel_cal_x', 'accel_cal_y', 'accel_cal_z'] + ordered_fieldnames = [ 'mag_declination', 'raw_press', 'raw_temp', 'gyro_cal_x', 'gyro_cal_y', 'gyro_cal_z', 'accel_cal_x', 'accel_cal_y', 'accel_cal_z', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z' ] + format = ' MAV. Also + used to return a point from MAV -> GCS + ''' + id = MAVLINK_MSG_ID_FENCE_POINT + name = 'FENCE_POINT' + fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng'] + ordered_fieldnames = [ 'lat', 'lng', 'target_system', 'target_component', 'idx', 'count' ] + format = ' MAV. Also + used to return a point from MAV -> GCS + ''' + id = MAVLINK_MSG_ID_RALLY_POINT + name = 'RALLY_POINT' + fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng', 'alt', 'break_alt', 'land_dir', 'flags'] + ordered_fieldnames = [ 'lat', 'lng', 'alt', 'break_alt', 'land_dir', 'target_system', 'target_component', 'idx', 'count', 'flags' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' MAV. Also used to + return a point from MAV -> GCS + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + count : total number of points (for sanity checking) (uint8_t) + lat : Latitude of point (float) + lng : Longitude of point (float) + + ''' + return MAVLink_fence_point_message(target_system, target_component, idx, count, lat, lng) + + def fence_point_send(self, target_system, target_component, idx, count, lat, lng): + ''' + A fence point. Used to set a point when from GCS -> MAV. Also used to + return a point from MAV -> GCS + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + count : total number of points (for sanity checking) (uint8_t) + lat : Latitude of point (float) + lng : Longitude of point (float) + + ''' + return self.send(self.fence_point_encode(target_system, target_component, idx, count, lat, lng)) + + def fence_fetch_point_encode(self, target_system, target_component, idx): + ''' + Request a current fence point from MAV + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + + ''' + return MAVLink_fence_fetch_point_message(target_system, target_component, idx) + + def fence_fetch_point_send(self, target_system, target_component, idx): + ''' + Request a current fence point from MAV + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 1, 0 is for return point) (uint8_t) + + ''' + return self.send(self.fence_fetch_point_encode(target_system, target_component, idx)) + + def fence_status_encode(self, breach_status, breach_count, breach_type, breach_time): + ''' + Status of geo-fencing. Sent in extended status stream when fencing + enabled + + breach_status : 0 if currently inside fence, 1 if outside (uint8_t) + breach_count : number of fence breaches (uint16_t) + breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) + breach_time : time of last breach in milliseconds since boot (uint32_t) + + ''' + return MAVLink_fence_status_message(breach_status, breach_count, breach_type, breach_time) + + def fence_status_send(self, breach_status, breach_count, breach_type, breach_time): + ''' + Status of geo-fencing. Sent in extended status stream when fencing + enabled + + breach_status : 0 if currently inside fence, 1 if outside (uint8_t) + breach_count : number of fence breaches (uint16_t) + breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) + breach_time : time of last breach in milliseconds since boot (uint32_t) + + ''' + return self.send(self.fence_status_encode(breach_status, breach_count, breach_type, breach_time)) + + def ahrs_encode(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): + ''' + Status of DCM attitude estimator + + omegaIx : X gyro drift estimate rad/s (float) + omegaIy : Y gyro drift estimate rad/s (float) + omegaIz : Z gyro drift estimate rad/s (float) + accel_weight : average accel_weight (float) + renorm_val : average renormalisation value (float) + error_rp : average error_roll_pitch value (float) + error_yaw : average error_yaw value (float) + + ''' + return MAVLink_ahrs_message(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw) + + def ahrs_send(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): + ''' + Status of DCM attitude estimator + + omegaIx : X gyro drift estimate rad/s (float) + omegaIy : Y gyro drift estimate rad/s (float) + omegaIz : Z gyro drift estimate rad/s (float) + accel_weight : average accel_weight (float) + renorm_val : average renormalisation value (float) + error_rp : average error_roll_pitch value (float) + error_yaw : average error_yaw value (float) + + ''' + return self.send(self.ahrs_encode(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw)) + + def simstate_encode(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lng): + ''' + Status of simulation environment, if used + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees * 1E7 (int32_t) + lng : Longitude in degrees * 1E7 (int32_t) + + ''' + return MAVLink_simstate_message(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lng) + + def simstate_send(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lng): + ''' + Status of simulation environment, if used + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees * 1E7 (int32_t) + lng : Longitude in degrees * 1E7 (int32_t) + + ''' + return self.send(self.simstate_encode(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lng)) + + def hwstatus_encode(self, Vcc, I2Cerr): + ''' + Status of key hardware + + Vcc : board voltage (mV) (uint16_t) + I2Cerr : I2C error count (uint8_t) + + ''' + return MAVLink_hwstatus_message(Vcc, I2Cerr) + + def hwstatus_send(self, Vcc, I2Cerr): + ''' + Status of key hardware + + Vcc : board voltage (mV) (uint16_t) + I2Cerr : I2C error count (uint8_t) + + ''' + return self.send(self.hwstatus_encode(Vcc, I2Cerr)) + + def radio_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio + + rssi : local signal strength (uint8_t) + remrssi : remote signal strength (uint8_t) + txbuf : how full the tx buffer is as a percentage (uint8_t) + noise : background noise level (uint8_t) + remnoise : remote background noise level (uint8_t) + rxerrors : receive errors (uint16_t) + fixed : count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio + + rssi : local signal strength (uint8_t) + remrssi : remote signal strength (uint8_t) + txbuf : how full the tx buffer is as a percentage (uint8_t) + noise : background noise level (uint8_t) + remnoise : remote background noise level (uint8_t) + rxerrors : receive errors (uint16_t) + fixed : count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def limits_status_encode(self, limits_state, last_trigger, last_action, last_recovery, last_clear, breach_count, mods_enabled, mods_required, mods_triggered): + ''' + Status of AP_Limits. Sent in extended status stream when AP_Limits is + enabled + + limits_state : state of AP_Limits, (see enum LimitState, LIMITS_STATE) (uint8_t) + last_trigger : time of last breach in milliseconds since boot (uint32_t) + last_action : time of last recovery action in milliseconds since boot (uint32_t) + last_recovery : time of last successful recovery in milliseconds since boot (uint32_t) + last_clear : time of last all-clear in milliseconds since boot (uint32_t) + breach_count : number of fence breaches (uint16_t) + mods_enabled : AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) (uint8_t) + mods_required : AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) (uint8_t) + mods_triggered : AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) (uint8_t) + + ''' + return MAVLink_limits_status_message(limits_state, last_trigger, last_action, last_recovery, last_clear, breach_count, mods_enabled, mods_required, mods_triggered) + + def limits_status_send(self, limits_state, last_trigger, last_action, last_recovery, last_clear, breach_count, mods_enabled, mods_required, mods_triggered): + ''' + Status of AP_Limits. Sent in extended status stream when AP_Limits is + enabled + + limits_state : state of AP_Limits, (see enum LimitState, LIMITS_STATE) (uint8_t) + last_trigger : time of last breach in milliseconds since boot (uint32_t) + last_action : time of last recovery action in milliseconds since boot (uint32_t) + last_recovery : time of last successful recovery in milliseconds since boot (uint32_t) + last_clear : time of last all-clear in milliseconds since boot (uint32_t) + breach_count : number of fence breaches (uint16_t) + mods_enabled : AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) (uint8_t) + mods_required : AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) (uint8_t) + mods_triggered : AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) (uint8_t) + + ''' + return self.send(self.limits_status_encode(limits_state, last_trigger, last_action, last_recovery, last_clear, breach_count, mods_enabled, mods_required, mods_triggered)) + + def wind_encode(self, direction, speed, speed_z): + ''' + Wind estimation + + direction : wind direction that wind is coming from (degrees) (float) + speed : wind speed in ground plane (m/s) (float) + speed_z : vertical wind speed (m/s) (float) + + ''' + return MAVLink_wind_message(direction, speed, speed_z) + + def wind_send(self, direction, speed, speed_z): + ''' + Wind estimation + + direction : wind direction that wind is coming from (degrees) (float) + speed : wind speed in ground plane (m/s) (float) + speed_z : vertical wind speed (m/s) (float) + + ''' + return self.send(self.wind_encode(direction, speed, speed_z)) + + def data16_encode(self, type, len, data): + ''' + Data packet, size 16 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return MAVLink_data16_message(type, len, data) + + def data16_send(self, type, len, data): + ''' + Data packet, size 16 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return self.send(self.data16_encode(type, len, data)) + + def data32_encode(self, type, len, data): + ''' + Data packet, size 32 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return MAVLink_data32_message(type, len, data) + + def data32_send(self, type, len, data): + ''' + Data packet, size 32 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return self.send(self.data32_encode(type, len, data)) + + def data64_encode(self, type, len, data): + ''' + Data packet, size 64 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return MAVLink_data64_message(type, len, data) + + def data64_send(self, type, len, data): + ''' + Data packet, size 64 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return self.send(self.data64_encode(type, len, data)) + + def data96_encode(self, type, len, data): + ''' + Data packet, size 96 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return MAVLink_data96_message(type, len, data) + + def data96_send(self, type, len, data): + ''' + Data packet, size 96 + + type : data type (uint8_t) + len : data length (uint8_t) + data : raw data (uint8_t) + + ''' + return self.send(self.data96_encode(type, len, data)) + + def rangefinder_encode(self, distance, voltage): + ''' + Rangefinder reporting + + distance : distance in meters (float) + voltage : raw voltage if available, zero otherwise (float) + + ''' + return MAVLink_rangefinder_message(distance, voltage) + + def rangefinder_send(self, distance, voltage): + ''' + Rangefinder reporting + + distance : distance in meters (float) + voltage : raw voltage if available, zero otherwise (float) + + ''' + return self.send(self.rangefinder_encode(distance, voltage)) + + def airspeed_autocal_encode(self, vx, vy, vz, diff_pressure, EAS2TAS, ratio, state_x, state_y, state_z, Pax, Pby, Pcz): + ''' + Airspeed auto-calibration + + vx : GPS velocity north m/s (float) + vy : GPS velocity east m/s (float) + vz : GPS velocity down m/s (float) + diff_pressure : Differential pressure pascals (float) + EAS2TAS : Estimated to true airspeed ratio (float) + ratio : Airspeed ratio (float) + state_x : EKF state x (float) + state_y : EKF state y (float) + state_z : EKF state z (float) + Pax : EKF Pax (float) + Pby : EKF Pby (float) + Pcz : EKF Pcz (float) + + ''' + return MAVLink_airspeed_autocal_message(vx, vy, vz, diff_pressure, EAS2TAS, ratio, state_x, state_y, state_z, Pax, Pby, Pcz) + + def airspeed_autocal_send(self, vx, vy, vz, diff_pressure, EAS2TAS, ratio, state_x, state_y, state_z, Pax, Pby, Pcz): + ''' + Airspeed auto-calibration + + vx : GPS velocity north m/s (float) + vy : GPS velocity east m/s (float) + vz : GPS velocity down m/s (float) + diff_pressure : Differential pressure pascals (float) + EAS2TAS : Estimated to true airspeed ratio (float) + ratio : Airspeed ratio (float) + state_x : EKF state x (float) + state_y : EKF state y (float) + state_z : EKF state z (float) + Pax : EKF Pax (float) + Pby : EKF Pby (float) + Pcz : EKF Pcz (float) + + ''' + return self.send(self.airspeed_autocal_encode(vx, vy, vz, diff_pressure, EAS2TAS, ratio, state_x, state_y, state_z, Pax, Pby, Pcz)) + + def rally_point_encode(self, target_system, target_component, idx, count, lat, lng, alt, break_alt, land_dir, flags): + ''' + A rally point. Used to set a point when from GCS -> MAV. Also used to + return a point from MAV -> GCS + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 0) (uint8_t) + count : total number of points (for sanity checking) (uint8_t) + lat : Latitude of point in degrees * 1E7 (int32_t) + lng : Longitude of point in degrees * 1E7 (int32_t) + alt : Transit / loiter altitude in meters relative to home (int16_t) + break_alt : Break altitude in meters relative to home (int16_t) + land_dir : Heading to aim for when landing. In centi-degrees. (uint16_t) + flags : See RALLY_FLAGS enum for definition of the bitmask. (uint8_t) + + ''' + return MAVLink_rally_point_message(target_system, target_component, idx, count, lat, lng, alt, break_alt, land_dir, flags) + + def rally_point_send(self, target_system, target_component, idx, count, lat, lng, alt, break_alt, land_dir, flags): + ''' + A rally point. Used to set a point when from GCS -> MAV. Also used to + return a point from MAV -> GCS + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 0) (uint8_t) + count : total number of points (for sanity checking) (uint8_t) + lat : Latitude of point in degrees * 1E7 (int32_t) + lng : Longitude of point in degrees * 1E7 (int32_t) + alt : Transit / loiter altitude in meters relative to home (int16_t) + break_alt : Break altitude in meters relative to home (int16_t) + land_dir : Heading to aim for when landing. In centi-degrees. (uint16_t) + flags : See RALLY_FLAGS enum for definition of the bitmask. (uint8_t) + + ''' + return self.send(self.rally_point_encode(target_system, target_component, idx, count, lat, lng, alt, break_alt, land_dir, flags)) + + def rally_fetch_point_encode(self, target_system, target_component, idx): + ''' + Request a current rally point from MAV. MAV should respond with a + RALLY_POINT message. MAV should not respond if the + request is invalid. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 0) (uint8_t) + + ''' + return MAVLink_rally_fetch_point_message(target_system, target_component, idx) + + def rally_fetch_point_send(self, target_system, target_component, idx): + ''' + Request a current rally point from MAV. MAV should respond with a + RALLY_POINT message. MAV should not respond if the + request is invalid. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + idx : point index (first point is 0) (uint8_t) + + ''' + return self.send(self.rally_fetch_point_encode(target_system, target_component, idx)) + + def compassmot_status_encode(self, throttle, current, interference, CompensationX, CompensationY, CompensationZ): + ''' + Status of compassmot calibration + + throttle : throttle (percent*10) (uint16_t) + current : current (amps) (float) + interference : interference (percent) (uint16_t) + CompensationX : Motor Compensation X (float) + CompensationY : Motor Compensation Y (float) + CompensationZ : Motor Compensation Z (float) + + ''' + return MAVLink_compassmot_status_message(throttle, current, interference, CompensationX, CompensationY, CompensationZ) + + def compassmot_status_send(self, throttle, current, interference, CompensationX, CompensationY, CompensationZ): + ''' + Status of compassmot calibration + + throttle : throttle (percent*10) (uint16_t) + current : current (amps) (float) + interference : interference (percent) (uint16_t) + CompensationX : Motor Compensation X (float) + CompensationY : Motor Compensation Y (float) + CompensationZ : Motor Compensation Z (float) + + ''' + return self.send(self.compassmot_status_encode(throttle, current, interference, CompensationX, CompensationY, CompensationZ)) + + def ahrs2_encode(self, roll, pitch, yaw, altitude, lat, lng): + ''' + Status of secondary AHRS filter if available + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + altitude : Altitude (MSL) (float) + lat : Latitude in degrees * 1E7 (int32_t) + lng : Longitude in degrees * 1E7 (int32_t) + + ''' + return MAVLink_ahrs2_message(roll, pitch, yaw, altitude, lat, lng) + + def ahrs2_send(self, roll, pitch, yaw, altitude, lat, lng): + ''' + Status of secondary AHRS filter if available + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + altitude : Altitude (MSL) (float) + lat : Latitude in degrees * 1E7 (int32_t) + lng : Longitude in degrees * 1E7 (int32_t) + + ''' + return self.send(self.ahrs2_encode(roll, pitch, yaw, altitude, lat, lng)) + + def camera_status_encode(self, time_usec, target_system, cam_idx, img_idx, event_id, p1, p2, p3, p4): + ''' + Camera Event + + time_usec : Image timestamp (microseconds since UNIX epoch, according to camera clock) (uint64_t) + target_system : System ID (uint8_t) + cam_idx : Camera ID (uint8_t) + img_idx : Image index (uint16_t) + event_id : See CAMERA_STATUS_TYPES enum for definition of the bitmask (uint8_t) + p1 : Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + p2 : Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + p3 : Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + p4 : Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + + ''' + return MAVLink_camera_status_message(time_usec, target_system, cam_idx, img_idx, event_id, p1, p2, p3, p4) + + def camera_status_send(self, time_usec, target_system, cam_idx, img_idx, event_id, p1, p2, p3, p4): + ''' + Camera Event + + time_usec : Image timestamp (microseconds since UNIX epoch, according to camera clock) (uint64_t) + target_system : System ID (uint8_t) + cam_idx : Camera ID (uint8_t) + img_idx : Image index (uint16_t) + event_id : See CAMERA_STATUS_TYPES enum for definition of the bitmask (uint8_t) + p1 : Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + p2 : Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + p3 : Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + p4 : Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) (float) + + ''' + return self.send(self.camera_status_encode(time_usec, target_system, cam_idx, img_idx, event_id, p1, p2, p3, p4)) + + def camera_feedback_encode(self, time_usec, target_system, cam_idx, img_idx, lat, lng, alt_msl, alt_rel, roll, pitch, yaw, foc_len, flags): + ''' + Camera Capture Feedback + + time_usec : Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) (uint64_t) + target_system : System ID (uint8_t) + cam_idx : Camera ID (uint8_t) + img_idx : Image index (uint16_t) + lat : Latitude in (deg * 1E7) (int32_t) + lng : Longitude in (deg * 1E7) (int32_t) + alt_msl : Altitude Absolute (meters AMSL) (float) + alt_rel : Altitude Relative (meters above HOME location) (float) + roll : Camera Roll angle (earth frame, degrees, +-180) (float) + pitch : Camera Pitch angle (earth frame, degrees, +-180) (float) + yaw : Camera Yaw (earth frame, degrees, 0-360, true) (float) + foc_len : Focal Length (mm) (float) + flags : See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask (uint8_t) + + ''' + return MAVLink_camera_feedback_message(time_usec, target_system, cam_idx, img_idx, lat, lng, alt_msl, alt_rel, roll, pitch, yaw, foc_len, flags) + + def camera_feedback_send(self, time_usec, target_system, cam_idx, img_idx, lat, lng, alt_msl, alt_rel, roll, pitch, yaw, foc_len, flags): + ''' + Camera Capture Feedback + + time_usec : Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) (uint64_t) + target_system : System ID (uint8_t) + cam_idx : Camera ID (uint8_t) + img_idx : Image index (uint16_t) + lat : Latitude in (deg * 1E7) (int32_t) + lng : Longitude in (deg * 1E7) (int32_t) + alt_msl : Altitude Absolute (meters AMSL) (float) + alt_rel : Altitude Relative (meters above HOME location) (float) + roll : Camera Roll angle (earth frame, degrees, +-180) (float) + pitch : Camera Pitch angle (earth frame, degrees, +-180) (float) + yaw : Camera Yaw (earth frame, degrees, 0-360, true) (float) + foc_len : Focal Length (mm) (float) + flags : See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask (uint8_t) + + ''' + return self.send(self.camera_feedback_encode(time_usec, target_system, cam_idx, img_idx, lat, lng, alt_msl, alt_rel, roll, pitch, yaw, foc_len, flags)) + + def battery2_encode(self, voltage, current_battery): + ''' + 2nd Battery status + + voltage : voltage in millivolts (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + + ''' + return MAVLink_battery2_message(voltage, current_battery) + + def battery2_send(self, voltage, current_battery): + ''' + 2nd Battery status + + voltage : voltage in millivolts (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + + ''' + return self.send(self.battery2_encode(voltage, current_battery)) + + def ahrs3_encode(self, roll, pitch, yaw, altitude, lat, lng, v1, v2, v3, v4): + ''' + Status of third AHRS filter if available. This is for ANU research + group (Ali and Sean) + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + altitude : Altitude (MSL) (float) + lat : Latitude in degrees * 1E7 (int32_t) + lng : Longitude in degrees * 1E7 (int32_t) + v1 : test variable1 (float) + v2 : test variable2 (float) + v3 : test variable3 (float) + v4 : test variable4 (float) + + ''' + return MAVLink_ahrs3_message(roll, pitch, yaw, altitude, lat, lng, v1, v2, v3, v4) + + def ahrs3_send(self, roll, pitch, yaw, altitude, lat, lng, v1, v2, v3, v4): + ''' + Status of third AHRS filter if available. This is for ANU research + group (Ali and Sean) + + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + altitude : Altitude (MSL) (float) + lat : Latitude in degrees * 1E7 (int32_t) + lng : Longitude in degrees * 1E7 (int32_t) + v1 : test variable1 (float) + v2 : test variable2 (float) + v3 : test variable3 (float) + v4 : test variable4 (float) + + ''' + return self.send(self.ahrs3_encode(roll, pitch, yaw, altitude, lat, lng, v1, v2, v3, v4)) + + def autopilot_version_request_encode(self, target_system, target_component): + ''' + Request the autopilot version from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_autopilot_version_request_message(target_system, target_component) + + def autopilot_version_request_send(self, target_system, target_component): + ''' + Request the autopilot version from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.autopilot_version_request_encode(target_system, target_component)) + + def remote_log_data_block_encode(self, target_system, target_component, seqno, data): + ''' + Send a block of log data to remote location + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seqno : log data block sequence number (uint32_t) + data : log data block (uint8_t) + + ''' + return MAVLink_remote_log_data_block_message(target_system, target_component, seqno, data) + + def remote_log_data_block_send(self, target_system, target_component, seqno, data): + ''' + Send a block of log data to remote location + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seqno : log data block sequence number (uint32_t) + data : log data block (uint8_t) + + ''' + return self.send(self.remote_log_data_block_encode(target_system, target_component, seqno, data)) + + def remote_log_block_status_encode(self, target_system, target_component, seqno, status): + ''' + Send Status of each log block that autopilot board might have sent + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seqno : log data block sequence number (uint32_t) + status : log data block status (uint8_t) + + ''' + return MAVLink_remote_log_block_status_message(target_system, target_component, seqno, status) + + def remote_log_block_status_send(self, target_system, target_component, seqno, status): + ''' + Send Status of each log block that autopilot board might have sent + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seqno : log data block sequence number (uint32_t) + status : log data block status (uint8_t) + + ''' + return self.send(self.remote_log_block_status_encode(target_system, target_component, seqno, status)) + + def led_control_encode(self, target_system, target_component, instance, pattern, custom_len, custom_bytes): + ''' + Control vehicle LEDs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + instance : Instance (LED instance to control or 255 for all LEDs) (uint8_t) + pattern : Pattern (see LED_PATTERN_ENUM) (uint8_t) + custom_len : Custom Byte Length (uint8_t) + custom_bytes : Custom Bytes (uint8_t) + + ''' + return MAVLink_led_control_message(target_system, target_component, instance, pattern, custom_len, custom_bytes) + + def led_control_send(self, target_system, target_component, instance, pattern, custom_len, custom_bytes): + ''' + Control vehicle LEDs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + instance : Instance (LED instance to control or 255 for all LEDs) (uint8_t) + pattern : Pattern (see LED_PATTERN_ENUM) (uint8_t) + custom_len : Custom Byte Length (uint8_t) + custom_bytes : Custom Bytes (uint8_t) + + ''' + return self.send(self.led_control_encode(target_system, target_component, instance, pattern, custom_len, custom_bytes)) + + def mag_cal_progress_encode(self, compass_id, cal_mask, cal_status, attempt, completion_pct, completion_mask, direction_x, direction_y, direction_z): + ''' + Reports progress of compass calibration. + + compass_id : Compass being calibrated (uint8_t) + cal_mask : Bitmask of compasses being calibrated (uint8_t) + cal_status : Status (see MAG_CAL_STATUS enum) (uint8_t) + attempt : Attempt number (uint8_t) + completion_pct : Completion percentage (uint8_t) + completion_mask : Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid) (uint8_t) + direction_x : Body frame direction vector for display (float) + direction_y : Body frame direction vector for display (float) + direction_z : Body frame direction vector for display (float) + + ''' + return MAVLink_mag_cal_progress_message(compass_id, cal_mask, cal_status, attempt, completion_pct, completion_mask, direction_x, direction_y, direction_z) + + def mag_cal_progress_send(self, compass_id, cal_mask, cal_status, attempt, completion_pct, completion_mask, direction_x, direction_y, direction_z): + ''' + Reports progress of compass calibration. + + compass_id : Compass being calibrated (uint8_t) + cal_mask : Bitmask of compasses being calibrated (uint8_t) + cal_status : Status (see MAG_CAL_STATUS enum) (uint8_t) + attempt : Attempt number (uint8_t) + completion_pct : Completion percentage (uint8_t) + completion_mask : Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid) (uint8_t) + direction_x : Body frame direction vector for display (float) + direction_y : Body frame direction vector for display (float) + direction_z : Body frame direction vector for display (float) + + ''' + return self.send(self.mag_cal_progress_encode(compass_id, cal_mask, cal_status, attempt, completion_pct, completion_mask, direction_x, direction_y, direction_z)) + + def mag_cal_report_encode(self, compass_id, cal_mask, cal_status, autosaved, fitness, ofs_x, ofs_y, ofs_z, diag_x, diag_y, diag_z, offdiag_x, offdiag_y, offdiag_z): + ''' + Reports results of completed compass calibration. Sent until + MAG_CAL_ACK received. + + compass_id : Compass being calibrated (uint8_t) + cal_mask : Bitmask of compasses being calibrated (uint8_t) + cal_status : Status (see MAG_CAL_STATUS enum) (uint8_t) + autosaved : 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters (uint8_t) + fitness : RMS milligauss residuals (float) + ofs_x : X offset (float) + ofs_y : Y offset (float) + ofs_z : Z offset (float) + diag_x : X diagonal (matrix 11) (float) + diag_y : Y diagonal (matrix 22) (float) + diag_z : Z diagonal (matrix 33) (float) + offdiag_x : X off-diagonal (matrix 12 and 21) (float) + offdiag_y : Y off-diagonal (matrix 13 and 31) (float) + offdiag_z : Z off-diagonal (matrix 32 and 23) (float) + + ''' + return MAVLink_mag_cal_report_message(compass_id, cal_mask, cal_status, autosaved, fitness, ofs_x, ofs_y, ofs_z, diag_x, diag_y, diag_z, offdiag_x, offdiag_y, offdiag_z) + + def mag_cal_report_send(self, compass_id, cal_mask, cal_status, autosaved, fitness, ofs_x, ofs_y, ofs_z, diag_x, diag_y, diag_z, offdiag_x, offdiag_y, offdiag_z): + ''' + Reports results of completed compass calibration. Sent until + MAG_CAL_ACK received. + + compass_id : Compass being calibrated (uint8_t) + cal_mask : Bitmask of compasses being calibrated (uint8_t) + cal_status : Status (see MAG_CAL_STATUS enum) (uint8_t) + autosaved : 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters (uint8_t) + fitness : RMS milligauss residuals (float) + ofs_x : X offset (float) + ofs_y : Y offset (float) + ofs_z : Z offset (float) + diag_x : X diagonal (matrix 11) (float) + diag_y : Y diagonal (matrix 22) (float) + diag_z : Z diagonal (matrix 33) (float) + offdiag_x : X off-diagonal (matrix 12 and 21) (float) + offdiag_y : Y off-diagonal (matrix 13 and 31) (float) + offdiag_z : Z off-diagonal (matrix 32 and 23) (float) + + ''' + return self.send(self.mag_cal_report_encode(compass_id, cal_mask, cal_status, autosaved, fitness, ofs_x, ofs_y, ofs_z, diag_x, diag_y, diag_z, offdiag_x, offdiag_y, offdiag_z)) + + def ekf_status_report_encode(self, flags, velocity_variance, pos_horiz_variance, pos_vert_variance, compass_variance, terrain_alt_variance): + ''' + EKF Status message including flags and variances + + flags : Flags (uint16_t) + velocity_variance : Velocity variance (float) + pos_horiz_variance : Horizontal Position variance (float) + pos_vert_variance : Vertical Position variance (float) + compass_variance : Compass variance (float) + terrain_alt_variance : Terrain Altitude variance (float) + + ''' + return MAVLink_ekf_status_report_message(flags, velocity_variance, pos_horiz_variance, pos_vert_variance, compass_variance, terrain_alt_variance) + + def ekf_status_report_send(self, flags, velocity_variance, pos_horiz_variance, pos_vert_variance, compass_variance, terrain_alt_variance): + ''' + EKF Status message including flags and variances + + flags : Flags (uint16_t) + velocity_variance : Velocity variance (float) + pos_horiz_variance : Horizontal Position variance (float) + pos_vert_variance : Vertical Position variance (float) + compass_variance : Compass variance (float) + terrain_alt_variance : Terrain Altitude variance (float) + + ''' + return self.send(self.ekf_status_report_encode(flags, velocity_variance, pos_horiz_variance, pos_vert_variance, compass_variance, terrain_alt_variance)) + + def pid_tuning_encode(self, axis, desired, achieved, FF, P, I, D): + ''' + PID tuning information + + axis : axis (uint8_t) + desired : desired rate (degrees/s) (float) + achieved : achieved rate (degrees/s) (float) + FF : FF component (float) + P : P component (float) + I : I component (float) + D : D component (float) + + ''' + return MAVLink_pid_tuning_message(axis, desired, achieved, FF, P, I, D) + + def pid_tuning_send(self, axis, desired, achieved, FF, P, I, D): + ''' + PID tuning information + + axis : axis (uint8_t) + desired : desired rate (degrees/s) (float) + achieved : achieved rate (degrees/s) (float) + FF : FF component (float) + P : P component (float) + I : I component (float) + D : D component (float) + + ''' + return self.send(self.pid_tuning_encode(axis, desired, achieved, FF, P, I, D)) + + def gimbal_report_encode(self, target_system, target_component, delta_time, delta_angle_x, delta_angle_y, delta_angle_z, delta_velocity_x, delta_velocity_y, delta_velocity_z, joint_roll, joint_el, joint_az): + ''' + 3 axis gimbal mesuraments + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + delta_time : Time since last update (seconds) (float) + delta_angle_x : Delta angle X (radians) (float) + delta_angle_y : Delta angle Y (radians) (float) + delta_angle_z : Delta angle X (radians) (float) + delta_velocity_x : Delta velocity X (m/s) (float) + delta_velocity_y : Delta velocity Y (m/s) (float) + delta_velocity_z : Delta velocity Z (m/s) (float) + joint_roll : Joint ROLL (radians) (float) + joint_el : Joint EL (radians) (float) + joint_az : Joint AZ (radians) (float) + + ''' + return MAVLink_gimbal_report_message(target_system, target_component, delta_time, delta_angle_x, delta_angle_y, delta_angle_z, delta_velocity_x, delta_velocity_y, delta_velocity_z, joint_roll, joint_el, joint_az) + + def gimbal_report_send(self, target_system, target_component, delta_time, delta_angle_x, delta_angle_y, delta_angle_z, delta_velocity_x, delta_velocity_y, delta_velocity_z, joint_roll, joint_el, joint_az): + ''' + 3 axis gimbal mesuraments + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + delta_time : Time since last update (seconds) (float) + delta_angle_x : Delta angle X (radians) (float) + delta_angle_y : Delta angle Y (radians) (float) + delta_angle_z : Delta angle X (radians) (float) + delta_velocity_x : Delta velocity X (m/s) (float) + delta_velocity_y : Delta velocity Y (m/s) (float) + delta_velocity_z : Delta velocity Z (m/s) (float) + joint_roll : Joint ROLL (radians) (float) + joint_el : Joint EL (radians) (float) + joint_az : Joint AZ (radians) (float) + + ''' + return self.send(self.gimbal_report_encode(target_system, target_component, delta_time, delta_angle_x, delta_angle_y, delta_angle_z, delta_velocity_x, delta_velocity_y, delta_velocity_z, joint_roll, joint_el, joint_az)) + + def gimbal_control_encode(self, target_system, target_component, demanded_rate_x, demanded_rate_y, demanded_rate_z): + ''' + Control message for rate gimbal + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + demanded_rate_x : Demanded angular rate X (rad/s) (float) + demanded_rate_y : Demanded angular rate Y (rad/s) (float) + demanded_rate_z : Demanded angular rate Z (rad/s) (float) + + ''' + return MAVLink_gimbal_control_message(target_system, target_component, demanded_rate_x, demanded_rate_y, demanded_rate_z) + + def gimbal_control_send(self, target_system, target_component, demanded_rate_x, demanded_rate_y, demanded_rate_z): + ''' + Control message for rate gimbal + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + demanded_rate_x : Demanded angular rate X (rad/s) (float) + demanded_rate_y : Demanded angular rate Y (rad/s) (float) + demanded_rate_z : Demanded angular rate Z (rad/s) (float) + + ''' + return self.send(self.gimbal_control_encode(target_system, target_component, demanded_rate_x, demanded_rate_y, demanded_rate_z)) + + def gimbal_torque_cmd_report_encode(self, target_system, target_component, rl_torque_cmd, el_torque_cmd, az_torque_cmd): + ''' + 100 Hz gimbal torque command telemetry + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + rl_torque_cmd : Roll Torque Command (int16_t) + el_torque_cmd : Elevation Torque Command (int16_t) + az_torque_cmd : Azimuth Torque Command (int16_t) + + ''' + return MAVLink_gimbal_torque_cmd_report_message(target_system, target_component, rl_torque_cmd, el_torque_cmd, az_torque_cmd) + + def gimbal_torque_cmd_report_send(self, target_system, target_component, rl_torque_cmd, el_torque_cmd, az_torque_cmd): + ''' + 100 Hz gimbal torque command telemetry + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + rl_torque_cmd : Roll Torque Command (int16_t) + el_torque_cmd : Elevation Torque Command (int16_t) + az_torque_cmd : Azimuth Torque Command (int16_t) + + ''' + return self.send(self.gimbal_torque_cmd_report_encode(target_system, target_component, rl_torque_cmd, el_torque_cmd, az_torque_cmd)) + + def gopro_heartbeat_encode(self, status, capture_mode, flags): + ''' + Heartbeat from a HeroBus attached GoPro + + status : Status (uint8_t) + capture_mode : Current capture mode (uint8_t) + flags : additional status bits (uint8_t) + + ''' + return MAVLink_gopro_heartbeat_message(status, capture_mode, flags) + + def gopro_heartbeat_send(self, status, capture_mode, flags): + ''' + Heartbeat from a HeroBus attached GoPro + + status : Status (uint8_t) + capture_mode : Current capture mode (uint8_t) + flags : additional status bits (uint8_t) + + ''' + return self.send(self.gopro_heartbeat_encode(status, capture_mode, flags)) + + def gopro_get_request_encode(self, target_system, target_component, cmd_id): + ''' + Request a GOPRO_COMMAND response from the GoPro + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + cmd_id : Command ID (uint8_t) + + ''' + return MAVLink_gopro_get_request_message(target_system, target_component, cmd_id) + + def gopro_get_request_send(self, target_system, target_component, cmd_id): + ''' + Request a GOPRO_COMMAND response from the GoPro + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + cmd_id : Command ID (uint8_t) + + ''' + return self.send(self.gopro_get_request_encode(target_system, target_component, cmd_id)) + + def gopro_get_response_encode(self, cmd_id, status, value): + ''' + Response from a GOPRO_COMMAND get request + + cmd_id : Command ID (uint8_t) + status : Status (uint8_t) + value : Value (uint8_t) + + ''' + return MAVLink_gopro_get_response_message(cmd_id, status, value) + + def gopro_get_response_send(self, cmd_id, status, value): + ''' + Response from a GOPRO_COMMAND get request + + cmd_id : Command ID (uint8_t) + status : Status (uint8_t) + value : Value (uint8_t) + + ''' + return self.send(self.gopro_get_response_encode(cmd_id, status, value)) + + def gopro_set_request_encode(self, target_system, target_component, cmd_id, value): + ''' + Request to set a GOPRO_COMMAND with a desired + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + cmd_id : Command ID (uint8_t) + value : Value (uint8_t) + + ''' + return MAVLink_gopro_set_request_message(target_system, target_component, cmd_id, value) + + def gopro_set_request_send(self, target_system, target_component, cmd_id, value): + ''' + Request to set a GOPRO_COMMAND with a desired + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + cmd_id : Command ID (uint8_t) + value : Value (uint8_t) + + ''' + return self.send(self.gopro_set_request_encode(target_system, target_component, cmd_id, value)) + + def gopro_set_response_encode(self, cmd_id, status): + ''' + Response from a GOPRO_COMMAND set request + + cmd_id : Command ID (uint8_t) + status : Status (uint8_t) + + ''' + return MAVLink_gopro_set_response_message(cmd_id, status) + + def gopro_set_response_send(self, cmd_id, status): + ''' + Response from a GOPRO_COMMAND set request + + cmd_id : Command ID (uint8_t) + status : Status (uint8_t) + + ''' + return self.send(self.gopro_set_response_encode(cmd_id, status)) + + def rpm_encode(self, rpm1, rpm2): + ''' + RPM sensor output + + rpm1 : RPM Sensor1 (float) + rpm2 : RPM Sensor2 (float) + + ''' + return MAVLink_rpm_message(rpm1, rpm2) + + def rpm_send(self, rpm1, rpm2): + ''' + RPM sensor output + + rpm1 : RPM Sensor1 (float) + rpm2 : RPM Sensor2 (float) + + ''' + return self.send(self.rpm_encode(rpm1, rpm2)) + + def heartbeat_encode(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): + ''' + The heartbeat message shows that a system is present and responding. + The type of the MAV and Autopilot hardware allow the + receiving system to treat further messages from this + system appropriate (e.g. by laying out the user + interface based on the autopilot). + + type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) + autopilot : Autopilot type / class. defined in MAV_AUTOPILOT ENUM (uint8_t) + base_mode : System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h (uint8_t) + custom_mode : A bitfield for use for autopilot-specific flags. (uint32_t) + system_status : System status flag, see MAV_STATE ENUM (uint8_t) + mavlink_version : MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version (uint8_t) + + ''' + return MAVLink_heartbeat_message(type, autopilot, base_mode, custom_mode, system_status, mavlink_version) + + def heartbeat_send(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): + ''' + The heartbeat message shows that a system is present and responding. + The type of the MAV and Autopilot hardware allow the + receiving system to treat further messages from this + system appropriate (e.g. by laying out the user + interface based on the autopilot). + + type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) + autopilot : Autopilot type / class. defined in MAV_AUTOPILOT ENUM (uint8_t) + base_mode : System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h (uint8_t) + custom_mode : A bitfield for use for autopilot-specific flags. (uint32_t) + system_status : System status flag, see MAV_STATE ENUM (uint8_t) + mavlink_version : MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version (uint8_t) + + ''' + return self.send(self.heartbeat_encode(type, autopilot, base_mode, custom_mode, system_status, mavlink_version)) + + def sys_status_encode(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) + drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_count1 : Autopilot-specific errors (uint16_t) + errors_count2 : Autopilot-specific errors (uint16_t) + errors_count3 : Autopilot-specific errors (uint16_t) + errors_count4 : Autopilot-specific errors (uint16_t) + + ''' + return MAVLink_sys_status_message(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4) + + def sys_status_send(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) + drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_count1 : Autopilot-specific errors (uint16_t) + errors_count2 : Autopilot-specific errors (uint16_t) + errors_count3 : Autopilot-specific errors (uint16_t) + errors_count4 : Autopilot-specific errors (uint16_t) + + ''' + return self.send(self.sys_status_encode(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4)) + + def system_time_encode(self, time_unix_usec, time_boot_ms): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + + time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) + time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) + + ''' + return MAVLink_system_time_message(time_unix_usec, time_boot_ms) + + def system_time_send(self, time_unix_usec, time_boot_ms): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + + time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) + time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) + + ''' + return self.send(self.system_time_encode(time_unix_usec, time_boot_ms)) + + def ping_encode(self, time_usec, seq, target_system, target_component): + ''' + A ping message either requesting or responding to a ping. This allows + to measure the system latencies, including serial + port, radio modem and UDP connections. + + time_usec : Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) (uint64_t) + seq : PING sequence (uint32_t) + target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + + ''' + return MAVLink_ping_message(time_usec, seq, target_system, target_component) + + def ping_send(self, time_usec, seq, target_system, target_component): + ''' + A ping message either requesting or responding to a ping. This allows + to measure the system latencies, including serial + port, radio modem and UDP connections. + + time_usec : Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) (uint64_t) + seq : PING sequence (uint32_t) + target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + + ''' + return self.send(self.ping_encode(time_usec, seq, target_system, target_component)) + + def change_operator_control_encode(self, target_system, control_request, version, passkey): + ''' + Request to control this MAV + + target_system : System the GCS requests control for (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) + passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) + + ''' + return MAVLink_change_operator_control_message(target_system, control_request, version, passkey) + + def change_operator_control_send(self, target_system, control_request, version, passkey): + ''' + Request to control this MAV + + target_system : System the GCS requests control for (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) + passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) + + ''' + return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) + + def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): + ''' + Accept / deny control of this MAV + + gcs_system_id : ID of the GCS this message (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) + + ''' + return MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) + + def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): + ''' + Accept / deny control of this MAV + + gcs_system_id : ID of the GCS this message (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) + + ''' + return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) + + def auth_key_encode(self, key): + ''' + Emit an encrypted signature / key identifying this system. PLEASE + NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for + true safety. + + key : key (char) + + ''' + return MAVLink_auth_key_message(key) + + def auth_key_send(self, key): + ''' + Emit an encrypted signature / key identifying this system. PLEASE + NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for + true safety. + + key : key (char) + + ''' + return self.send(self.auth_key_encode(key)) + + def set_mode_encode(self, target_system, base_mode, custom_mode): + ''' + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with + MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as + defined by enum MAV_MODE. There is no target component + id as the mode is by definition for the overall + aircraft, not only for one component. + + target_system : The system setting the mode (uint8_t) + base_mode : The new base mode (uint8_t) + custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) + + ''' + return MAVLink_set_mode_message(target_system, base_mode, custom_mode) + + def set_mode_send(self, target_system, base_mode, custom_mode): + ''' + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with + MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as + defined by enum MAV_MODE. There is no target component + id as the mode is by definition for the overall + aircraft, not only for one component. + + target_system : The system setting the mode (uint8_t) + base_mode : The new base mode (uint8_t) + custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) + + ''' + return self.send(self.set_mode_encode(target_system, base_mode, custom_mode)) + + def param_request_read_encode(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/ardupilotmega.xml b/pymavlink/dialects/v10/ardupilotmega.xml new file mode 100644 index 0000000..e04c0b1 --- /dev/null +++ b/pymavlink/dialects/v10/ardupilotmega.xml @@ -0,0 +1,1564 @@ + + + common.xml + + + + + + Mission command to perform motor test + motor sequence number (a number from 1 to max number of motors on the vehicle) + throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) + throttle + timeout (in seconds) + Empty + Empty + Empty + + + + Mission command to operate EPM gripper + gripper number (a number from 1 to max number of grippers on the vehicle) + gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum) + Empty + Empty + Empty + Empty + Empty + + + + Enable/disable autotune + enable (1: enable, 0:disable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. + altitude (m) + descent speed (m/s) + Wiggle Time (s) + Empty + Empty + Empty + Empty + + + + A system wide power-off event has been initiated. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + FLY button has been clicked. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + FLY button has been held for 1.5 seconds. + Takeoff altitude + Empty + Empty + Empty + Empty + Empty + Empty + + + + PAUSE button has been clicked. + 1 if Solo is in a shot mode, 0 otherwise + Empty + Empty + Empty + Empty + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Automatically retry on failure (0=no retry, 1=retry). + Save without user input (0=require input, 1=autosave). + Delay (seconds) + Autoreboot (0=user reboot, 1=autoreboot) + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Cancel a running magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reply with the version banner + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Causes the gimbal to reset and boot as if it was just powered on + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Command autopilot to get into factory test/diagnostic mode + 0 means get out of test mode, 1 means get into test mode + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reports progress and success or failure of gimbal axis calibration procedure + Gimbal axis we're reporting calibration progress for + Current calibration progress for this axis, 0x64=100% + Status of the calibration + Empty + Empty + Empty + Empty + + + + Starts commutation calibration on the gimbal + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Erases gimbal application and parameters + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + a limit has been breached + + + + taking action eg. RTL + + + + we're no longer in breach of a limit + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + + + Flags in RALLY_POINT message + + Flag set when requiring favorable winds for landing. + + + + Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. + + + + + + + Disable parachute release + + + + Enable parachute release + + + + Release parachute + + + + + + + throttle as a percentage from 0 ~ 100 + + + + throttle as an absolute PWM value (normally in range of 1000~2000) + + + + throttle pass-through from pilot's transmitter + + + + + + Gripper actions. + + gripper release of cargo + + + + gripper grabs onto cargo + + + + + + + Camera heartbeat, announce camera component ID at 1hz + + + + Camera image triggered + + + + Camera connection lost + + + + Camera unknown error + + + + Camera battery low. Parameter p1 shows reported voltage + + + + Camera storage low. Parameter p1 shows reported shots remaining + + + + Camera storage low. Parameter p1 shows reported video minutes remaining + + + + + + + Shooting photos, not video + + + + Shooting video, not stills + + + + Unable to achieve requested exposure (e.g. shutter speed too low) + + + + Closed loop feedback from camera, we know for sure it has successfully taken a picture + + + + Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture + + + + + + + Gimbal is powered on but has not started initializing yet + + + + Gimbal is currently running calibration on the pitch axis + + + + Gimbal is currently running calibration on the roll axis + + + + Gimbal is currently running calibration on the yaw axis + + + + Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter + + + + Gimbal is actively stabilizing + + + + Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command + + + + + + Gimbal yaw axis + + + + Gimbal pitch axis + + + + Gimbal roll axis + + + + + + Axis calibration is in progress + + + + Axis calibration succeeded + + + + Axis calibration failed + + + + + + Whether or not this axis requires calibration is unknown at this time + + + + This axis requires calibration + + + + This axis does not require calibration + + + + + + + No GoPro connected + + + + The detected GoPro is not HeroBus compatible + + + + A HeroBus compatible GoPro is connected + + + + An unrecoverable error was encountered with the connected GoPro, it may require a power cycle + + + + + + + GoPro is currently recording + + + + + + The write message with ID indicated succeeded + + + + The write message with ID indicated failed + + + + + + (Get/Set) + + + + (Get/Set) + + + + (___/Set) + + + + (Get/___) + + + + (Get/___) + + + + (Get/Set) + + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) + + + + + (Get/Set) + + + + + + Video mode + + + + Photo mode + + + + Burst mode, hero 3+ only + + + + Time lapse mode, hero 3+ only + + + + Multi shot mode, hero 4 only + + + + Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black + + + + Playback mode, hero 4 only + + + + Mode not yet known + + + + + + 848 x 480 (480p) + + + + 1280 x 720 (720p) + + + + 1280 x 960 (960p) + + + + 1920 x 1080 (1080p) + + + + 1920 x 1440 (1440p) + + + + 2704 x 1440 (2.7k-17:9) + + + + 2704 x 1524 (2.7k-16:9) + + + + 2704 x 2028 (2.7k-4:3) + + + + 3840 x 2160 (4k-16:9) + + + + 4096 x 2160 (4k-17:9) + + + + 1280 x 720 (720p-SuperView) + + + + 1920 x 1080 (1080p-SuperView) + + + + 2704 x 1520 (2.7k-SuperView) + + + + 3840 x 2160 (4k-SuperView) + + + + + + 12 FPS + + + + 15 FPS + + + + 24 FPS + + + + 25 FPS + + + + 30 FPS + + + + 48 FPS + + + + 50 FPS + + + + 60 FPS + + + + 80 FPS + + + + 90 FPS + + + + 100 FPS + + + + 120 FPS + + + + 240 FPS + + + + 12.5 FPS + + + + + + 0x00: Wide + + + + 0x01: Medium + + + + 0x02: Narrow + + + + + + 0=NTSC, 1=PAL + + + + + + 5MP Medium + + + + 7MP Medium + + + + 7MP Wide + + + + 10MP Wide + + + + 12MP Wide + + + + + + Auto + + + + 3000K + + + + 5500K + + + + 6500K + + + + Camera Raw + + + + + + Auto + + + + Neutral + + + + + + ISO 400 + + + + ISO 800 (Only Hero 4) + + + + ISO 1600 + + + + ISO 3200 (Only Hero 4) + + + + ISO 6400 + + + + + + Low Sharpness + + + + Medium Sharpness + + + + High Sharpness + + + + + + -5.0 EV (Hero 3+ Only) + + + + -4.5 EV (Hero 3+ Only) + + + + -4.0 EV (Hero 3+ Only) + + + + -3.5 EV (Hero 3+ Only) + + + + -3.0 EV (Hero 3+ Only) + + + + -2.5 EV (Hero 3+ Only) + + + + -2.0 EV + + + + -1.5 EV + + + + -1.0 EV + + + + -0.5 EV + + + + 0.0 EV + + + + +0.5 EV + + + + +1.0 EV + + + + +1.5 EV + + + + +2.0 EV + + + + +2.5 EV (Hero 3+ Only) + + + + +3.0 EV (Hero 3+ Only) + + + + +3.5 EV (Hero 3+ Only) + + + + +4.0 EV (Hero 3+ Only) + + + + +4.5 EV (Hero 3+ Only) + + + + +5.0 EV (Hero 3+ Only) + + + + + + Charging disabled + + + + Charging enabled + + + + + + Unknown gopro model + + + + Hero 3+ Silver (HeroBus not supported by GoPro) + + + + Hero 3+ Black + + + + Hero 4 Silver + + + + Hero 4 Black + + + + + + 3 Shots / 1 Second + + + + 5 Shots / 1 Second + + + + 10 Shots / 1 Second + + + + 10 Shots / 2 Second + + + + 10 Shots / 3 Second (Hero 4 Only) + + + + 30 Shots / 1 Second + + + + 30 Shots / 2 Second + + + + 30 Shots / 3 Second + + + + 30 Shots / 6 Second + + + + + + + LED patterns off (return control to regular vehicle control) + + + + LEDs show pattern during firmware update + + + + Custom Pattern using custom bytes fields + + + + + + Flags in EKF_STATUS message + + set if EKF's attitude estimate is good + + + + set if EKF's horizontal velocity estimate is good + + + + set if EKF's vertical velocity estimate is good + + + + set if EKF's horizontal position (relative) estimate is good + + + + set if EKF's horizontal position (absolute) estimate is good + + + + set if EKF's vertical position (absolute) estimate is good + + + + set if EKF's vertical position (above ground) estimate is good + + + + EKF is in constant position mode and does not know it's absolute or relative position + + + + set if EKF's predicted horizontal position (relative) estimate is good + + + + set if EKF's predicted horizontal position (absolute) estimate is good + + + + + + + + + + + + + + + + + + + + + + Special ACK block numbers control activation of dataflash log streaming + + + + UAV to stop sending DataFlash blocks + + + + + UAV to start sending DataFlash blocks + + + + + + + Possible remote log data block statuses + + This block has NOT been received + + + + This block has been received + + + + + + + Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + + Configure on-board Camera Control System. + System ID + Component ID + Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + Exposure type enumeration from 1 to N (0 means ignore) + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + Control on-board Camera Control System to take shots. + System ID + Component ID + 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + 1 to N //Zoom's absolute position (0 means ignore) + -100 to 100 //Zooming step value to offset zoom from the current position + 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + 0: ignore, 1: shot or start filming + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + + Message to configure a camera mount, directional antenna, etc. + System ID + Component ID + mount operating mode (see MAV_MOUNT_MODE enum) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + + + + Message to control a camera mount, directional antenna, etc. + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + + + + Message with some status from APM to GCS about camera or antenna mount + System ID + Component ID + pitch(deg*100) + roll(deg*100) + yaw(deg*100) + + + + + A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 1, 0 is for return point) + total number of points (for sanity checking) + Latitude of point + Longitude of point + + + + Request a current fence point from MAV + System ID + Component ID + point index (first point is 1, 0 is for return point) + + + + Status of geo-fencing. Sent in extended status stream when fencing enabled + 0 if currently inside fence, 1 if outside + number of fence breaches + last breach type (see FENCE_BREACH_* enum) + time of last breach in milliseconds since boot + + + + Status of DCM attitude estimator + X gyro drift estimate rad/s + Y gyro drift estimate rad/s + Z gyro drift estimate rad/s + average accel_weight + average renormalisation value + average error_roll_pitch value + average error_yaw value + + + + Status of simulation environment, if used + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + Status of key hardware + board voltage (mV) + I2C error count + + + + Status generated by radio + local signal strength + remote signal strength + how full the tx buffer is as a percentage + background noise level + remote background noise level + receive errors + count of error corrected packets + + + + + Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled + state of AP_Limits, (see enum LimitState, LIMITS_STATE) + time of last breach in milliseconds since boot + time of last recovery action in milliseconds since boot + time of last successful recovery in milliseconds since boot + time of last all-clear in milliseconds since boot + number of fence breaches + AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) + + + + Wind estimation + wind direction that wind is coming from (degrees) + wind speed in ground plane (m/s) + vertical wind speed (m/s) + + + + Data packet, size 16 + data type + data length + raw data + + + + Data packet, size 32 + data type + data length + raw data + + + + Data packet, size 64 + data type + data length + raw data + + + + Data packet, size 96 + data type + data length + raw data + + + + Rangefinder reporting + distance in meters + raw voltage if available, zero otherwise + + + + Airspeed auto-calibration + GPS velocity north m/s + GPS velocity east m/s + GPS velocity down m/s + Differential pressure pascals + Estimated to true airspeed ratio + Airspeed ratio + EKF state x + EKF state y + EKF state z + EKF Pax + EKF Pby + EKF Pcz + + + + + A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 0) + total number of points (for sanity checking) + Latitude of point in degrees * 1E7 + Longitude of point in degrees * 1E7 + Transit / loiter altitude in meters relative to home + + Break altitude in meters relative to home + Heading to aim for when landing. In centi-degrees. + See RALLY_FLAGS enum for definition of the bitmask. + + + + Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. + System ID + Component ID + point index (first point is 0) + + + + Status of compassmot calibration + throttle (percent*10) + current (amps) + interference (percent) + Motor Compensation X + Motor Compensation Y + Motor Compensation Z + + + + + Status of secondary AHRS filter if available + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + + Camera Event + Image timestamp (microseconds since UNIX epoch, according to camera clock) + System ID + + Camera ID + + Image index + + See CAMERA_STATUS_TYPES enum for definition of the bitmask + Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + + + + + Camera Capture Feedback + Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) + System ID + + Camera ID + + Image index + + Latitude in (deg * 1E7) + Longitude in (deg * 1E7) + Altitude Absolute (meters AMSL) + Altitude Relative (meters above HOME location) + Camera Roll angle (earth frame, degrees, +-180) + + Camera Pitch angle (earth frame, degrees, +-180) + + Camera Yaw (earth frame, degrees, 0-360, true) + + Focal Length (mm) + + See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + + + + + 2nd Battery status + voltage in millivolts + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + + + + Status of third AHRS filter if available. This is for ANU research group (Ali and Sean) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + test variable1 + test variable2 + test variable3 + test variable4 + + + + Request the autopilot version from the system/component. + System ID + Component ID + + + + + Send a block of log data to remote location + System ID + Component ID + log data block sequence number + log data block + + + + Send Status of each log block that autopilot board might have sent + System ID + Component ID + log data block sequence number + log data block status + + + + Control vehicle LEDs + System ID + Component ID + Instance (LED instance to control or 255 for all LEDs) + Pattern (see LED_PATTERN_ENUM) + Custom Byte Length + Custom Bytes + + + + Reports progress of compass calibration. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + Attempt number + Completion percentage + Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid) + Body frame direction vector for display + Body frame direction vector for display + Body frame direction vector for display + + + + Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters + RMS milligauss residuals + X offset + Y offset + Z offset + X diagonal (matrix 11) + Y diagonal (matrix 22) + Z diagonal (matrix 33) + X off-diagonal (matrix 12 and 21) + Y off-diagonal (matrix 13 and 31) + Z off-diagonal (matrix 32 and 23) + + + + + EKF Status message including flags and variances + Flags + + Velocity variance + + Horizontal Position variance + Vertical Position variance + Compass variance + Terrain Altitude variance + + + + + PID tuning information + axis + desired rate (degrees/s) + achieved rate (degrees/s) + FF component + P component + I component + D component + + + + 3 axis gimbal mesuraments + System ID + Component ID + Time since last update (seconds) + Delta angle X (radians) + Delta angle Y (radians) + Delta angle X (radians) + Delta velocity X (m/s) + Delta velocity Y (m/s) + Delta velocity Z (m/s) + Joint ROLL (radians) + Joint EL (radians) + Joint AZ (radians) + + + + Control message for rate gimbal + System ID + Component ID + Demanded angular rate X (rad/s) + Demanded angular rate Y (rad/s) + Demanded angular rate Z (rad/s) + + + + 100 Hz gimbal torque command telemetry + System ID + Component ID + Roll Torque Command + Elevation Torque Command + Azimuth Torque Command + + + + + Heartbeat from a HeroBus attached GoPro + Status + Current capture mode + additional status bits + + + + + Request a GOPRO_COMMAND response from the GoPro + System ID + Component ID + Command ID + + + + Response from a GOPRO_COMMAND get request + Command ID + Status + Value + + + + Request to set a GOPRO_COMMAND with a desired + System ID + Component ID + Command ID + Value + + + + Response from a GOPRO_COMMAND set request + Command ID + Status + + + + + RPM sensor output + RPM Sensor1 + RPM Sensor2 + + + diff --git a/pymavlink/dialects/v10/autoquad.py b/pymavlink/dialects/v10/autoquad.py new file mode 100644 index 0000000..a7d2322 --- /dev/null +++ b/pymavlink/dialects/v10/autoquad.py @@ -0,0 +1,11235 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: autoquad.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "autoquad" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_PROPULSION = 13 # Motor/ESC telemetry data. +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_PROPULSION', '''Motor/ESC telemetry data.''') +MAV_DATA_STREAM_ENUM_END = 14 # +enums['MAV_DATA_STREAM'][14] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_AUTOPILOT +enums['MAV_AUTOPILOT'] = {} +MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything +enums['MAV_AUTOPILOT'][0] = EnumEntry('MAV_AUTOPILOT_GENERIC', '''Generic autopilot, full support for everything''') +MAV_AUTOPILOT_RESERVED = 1 # Reserved for future use. +enums['MAV_AUTOPILOT'][1] = EnumEntry('MAV_AUTOPILOT_RESERVED', '''Reserved for future use.''') +MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu +enums['MAV_AUTOPILOT'][2] = EnumEntry('MAV_AUTOPILOT_SLUGS', '''SLUGS autopilot, http://slugsuav.soe.ucsc.edu''') +MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com +enums['MAV_AUTOPILOT'][3] = EnumEntry('MAV_AUTOPILOT_ARDUPILOTMEGA', '''ArduPilotMega / ArduCopter, http://diydrones.com''') +MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org +enums['MAV_AUTOPILOT'][4] = EnumEntry('MAV_AUTOPILOT_OPENPILOT', '''OpenPilot, http://openpilot.org''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints +enums['MAV_AUTOPILOT'][5] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY', '''Generic autopilot only supporting simple waypoints''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation + # commands +enums['MAV_AUTOPILOT'][6] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY', '''Generic autopilot supporting waypoints and other simple navigation commands''') +MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set +enums['MAV_AUTOPILOT'][7] = EnumEntry('MAV_AUTOPILOT_GENERIC_MISSION_FULL', '''Generic autopilot supporting the full mission command set''') +MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component +enums['MAV_AUTOPILOT'][8] = EnumEntry('MAV_AUTOPILOT_INVALID', '''No valid autopilot, e.g. a GCS or other MAVLink component''') +MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi +enums['MAV_AUTOPILOT'][9] = EnumEntry('MAV_AUTOPILOT_PPZ', '''PPZ UAV - http://nongnu.org/paparazzi''') +MAV_AUTOPILOT_UDB = 10 # UAV Dev Board +enums['MAV_AUTOPILOT'][10] = EnumEntry('MAV_AUTOPILOT_UDB', '''UAV Dev Board''') +MAV_AUTOPILOT_FP = 11 # FlexiPilot +enums['MAV_AUTOPILOT'][11] = EnumEntry('MAV_AUTOPILOT_FP', '''FlexiPilot''') +MAV_AUTOPILOT_PX4 = 12 # PX4 Autopilot - http://pixhawk.ethz.ch/px4/ +enums['MAV_AUTOPILOT'][12] = EnumEntry('MAV_AUTOPILOT_PX4', '''PX4 Autopilot - http://pixhawk.ethz.ch/px4/''') +MAV_AUTOPILOT_SMACCMPILOT = 13 # SMACCMPilot - http://smaccmpilot.org +enums['MAV_AUTOPILOT'][13] = EnumEntry('MAV_AUTOPILOT_SMACCMPILOT', '''SMACCMPilot - http://smaccmpilot.org''') +MAV_AUTOPILOT_AUTOQUAD = 14 # AutoQuad -- http://autoquad.org +enums['MAV_AUTOPILOT'][14] = EnumEntry('MAV_AUTOPILOT_AUTOQUAD', '''AutoQuad -- http://autoquad.org''') +MAV_AUTOPILOT_ARMAZILA = 15 # Armazila -- http://armazila.com +enums['MAV_AUTOPILOT'][15] = EnumEntry('MAV_AUTOPILOT_ARMAZILA', '''Armazila -- http://armazila.com''') +MAV_AUTOPILOT_AEROB = 16 # Aerob -- http://aerob.ru +enums['MAV_AUTOPILOT'][16] = EnumEntry('MAV_AUTOPILOT_AEROB', '''Aerob -- http://aerob.ru''') +MAV_AUTOPILOT_ASLUAV = 17 # ASLUAV autopilot -- http://www.asl.ethz.ch +enums['MAV_AUTOPILOT'][17] = EnumEntry('MAV_AUTOPILOT_ASLUAV', '''ASLUAV autopilot -- http://www.asl.ethz.ch''') +MAV_AUTOPILOT_ENUM_END = 18 # +enums['MAV_AUTOPILOT'][18] = EnumEntry('MAV_AUTOPILOT_ENUM_END', '''''') + +# MAV_TYPE +enums['MAV_TYPE'] = {} +MAV_TYPE_GENERIC = 0 # Generic micro air vehicle. +enums['MAV_TYPE'][0] = EnumEntry('MAV_TYPE_GENERIC', '''Generic micro air vehicle.''') +MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft. +enums['MAV_TYPE'][1] = EnumEntry('MAV_TYPE_FIXED_WING', '''Fixed wing aircraft.''') +MAV_TYPE_QUADROTOR = 2 # Quadrotor +enums['MAV_TYPE'][2] = EnumEntry('MAV_TYPE_QUADROTOR', '''Quadrotor''') +MAV_TYPE_COAXIAL = 3 # Coaxial helicopter +enums['MAV_TYPE'][3] = EnumEntry('MAV_TYPE_COAXIAL', '''Coaxial helicopter''') +MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor. +enums['MAV_TYPE'][4] = EnumEntry('MAV_TYPE_HELICOPTER', '''Normal helicopter with tail rotor.''') +MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation +enums['MAV_TYPE'][5] = EnumEntry('MAV_TYPE_ANTENNA_TRACKER', '''Ground installation''') +MAV_TYPE_GCS = 6 # Operator control unit / ground control station +enums['MAV_TYPE'][6] = EnumEntry('MAV_TYPE_GCS', '''Operator control unit / ground control station''') +MAV_TYPE_AIRSHIP = 7 # Airship, controlled +enums['MAV_TYPE'][7] = EnumEntry('MAV_TYPE_AIRSHIP', '''Airship, controlled''') +MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled +enums['MAV_TYPE'][8] = EnumEntry('MAV_TYPE_FREE_BALLOON', '''Free balloon, uncontrolled''') +MAV_TYPE_ROCKET = 9 # Rocket +enums['MAV_TYPE'][9] = EnumEntry('MAV_TYPE_ROCKET', '''Rocket''') +MAV_TYPE_GROUND_ROVER = 10 # Ground rover +enums['MAV_TYPE'][10] = EnumEntry('MAV_TYPE_GROUND_ROVER', '''Ground rover''') +MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship +enums['MAV_TYPE'][11] = EnumEntry('MAV_TYPE_SURFACE_BOAT', '''Surface vessel, boat, ship''') +MAV_TYPE_SUBMARINE = 12 # Submarine +enums['MAV_TYPE'][12] = EnumEntry('MAV_TYPE_SUBMARINE', '''Submarine''') +MAV_TYPE_HEXAROTOR = 13 # Hexarotor +enums['MAV_TYPE'][13] = EnumEntry('MAV_TYPE_HEXAROTOR', '''Hexarotor''') +MAV_TYPE_OCTOROTOR = 14 # Octorotor +enums['MAV_TYPE'][14] = EnumEntry('MAV_TYPE_OCTOROTOR', '''Octorotor''') +MAV_TYPE_TRICOPTER = 15 # Octorotor +enums['MAV_TYPE'][15] = EnumEntry('MAV_TYPE_TRICOPTER', '''Octorotor''') +MAV_TYPE_FLAPPING_WING = 16 # Flapping wing +enums['MAV_TYPE'][16] = EnumEntry('MAV_TYPE_FLAPPING_WING', '''Flapping wing''') +MAV_TYPE_KITE = 17 # Flapping wing +enums['MAV_TYPE'][17] = EnumEntry('MAV_TYPE_KITE', '''Flapping wing''') +MAV_TYPE_ONBOARD_CONTROLLER = 18 # Onboard companion controller +enums['MAV_TYPE'][18] = EnumEntry('MAV_TYPE_ONBOARD_CONTROLLER', '''Onboard companion controller''') +MAV_TYPE_VTOL_DUOROTOR = 19 # Two-rotor VTOL using control surfaces in vertical operation in + # addition. Tailsitter. +enums['MAV_TYPE'][19] = EnumEntry('MAV_TYPE_VTOL_DUOROTOR', '''Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.''') +MAV_TYPE_VTOL_QUADROTOR = 20 # Quad-rotor VTOL using a V-shaped quad config in vertical operation. + # Tailsitter. +enums['MAV_TYPE'][20] = EnumEntry('MAV_TYPE_VTOL_QUADROTOR', '''Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.''') +MAV_TYPE_VTOL_TILTROTOR = 21 # Tiltrotor VTOL +enums['MAV_TYPE'][21] = EnumEntry('MAV_TYPE_VTOL_TILTROTOR', '''Tiltrotor VTOL''') +MAV_TYPE_VTOL_RESERVED2 = 22 # VTOL reserved 2 +enums['MAV_TYPE'][22] = EnumEntry('MAV_TYPE_VTOL_RESERVED2', '''VTOL reserved 2''') +MAV_TYPE_VTOL_RESERVED3 = 23 # VTOL reserved 3 +enums['MAV_TYPE'][23] = EnumEntry('MAV_TYPE_VTOL_RESERVED3', '''VTOL reserved 3''') +MAV_TYPE_VTOL_RESERVED4 = 24 # VTOL reserved 4 +enums['MAV_TYPE'][24] = EnumEntry('MAV_TYPE_VTOL_RESERVED4', '''VTOL reserved 4''') +MAV_TYPE_VTOL_RESERVED5 = 25 # VTOL reserved 5 +enums['MAV_TYPE'][25] = EnumEntry('MAV_TYPE_VTOL_RESERVED5', '''VTOL reserved 5''') +MAV_TYPE_GIMBAL = 26 # Onboard gimbal +enums['MAV_TYPE'][26] = EnumEntry('MAV_TYPE_GIMBAL', '''Onboard gimbal''') +MAV_TYPE_ADSB = 27 # Onboard ADSB peripheral +enums['MAV_TYPE'][27] = EnumEntry('MAV_TYPE_ADSB', '''Onboard ADSB peripheral''') +MAV_TYPE_ENUM_END = 28 # +enums['MAV_TYPE'][28] = EnumEntry('MAV_TYPE_ENUM_END', '''''') + +# FIRMWARE_VERSION_TYPE +enums['FIRMWARE_VERSION_TYPE'] = {} +FIRMWARE_VERSION_TYPE_DEV = 0 # development release +enums['FIRMWARE_VERSION_TYPE'][0] = EnumEntry('FIRMWARE_VERSION_TYPE_DEV', '''development release''') +FIRMWARE_VERSION_TYPE_ALPHA = 64 # alpha release +enums['FIRMWARE_VERSION_TYPE'][64] = EnumEntry('FIRMWARE_VERSION_TYPE_ALPHA', '''alpha release''') +FIRMWARE_VERSION_TYPE_BETA = 128 # beta release +enums['FIRMWARE_VERSION_TYPE'][128] = EnumEntry('FIRMWARE_VERSION_TYPE_BETA', '''beta release''') +FIRMWARE_VERSION_TYPE_RC = 192 # release candidate +enums['FIRMWARE_VERSION_TYPE'][192] = EnumEntry('FIRMWARE_VERSION_TYPE_RC', '''release candidate''') +FIRMWARE_VERSION_TYPE_OFFICIAL = 255 # official stable release +enums['FIRMWARE_VERSION_TYPE'][255] = EnumEntry('FIRMWARE_VERSION_TYPE_OFFICIAL', '''official stable release''') +FIRMWARE_VERSION_TYPE_ENUM_END = 256 # +enums['FIRMWARE_VERSION_TYPE'][256] = EnumEntry('FIRMWARE_VERSION_TYPE_ENUM_END', '''''') + +# MAV_MODE_FLAG +enums['MAV_MODE_FLAG'] = {} +MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use. +enums['MAV_MODE_FLAG'][1] = EnumEntry('MAV_MODE_FLAG_CUSTOM_MODE_ENABLED', '''0b00000001 Reserved for future use.''') +MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for + # temporary system tests and should not be + # used for stable implementations. +enums['MAV_MODE_FLAG'][2] = EnumEntry('MAV_MODE_FLAG_TEST_ENABLED', '''0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.''') +MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal + # positions. Guided flag can be set or not, + # depends on the actual implementation. +enums['MAV_MODE_FLAG'][4] = EnumEntry('MAV_MODE_FLAG_AUTO_ENABLED', '''0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.''') +MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items. +enums['MAV_MODE_FLAG'][8] = EnumEntry('MAV_MODE_FLAG_GUIDED_ENABLED', '''0b00001000 guided mode enabled, system flies MISSIONs / mission items.''') +MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and + # optionally position). It needs however + # further control inputs to move around. +enums['MAV_MODE_FLAG'][16] = EnumEntry('MAV_MODE_FLAG_STABILIZE_ENABLED', '''0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.''') +MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are + # blocked, but internal software is full + # operational. +enums['MAV_MODE_FLAG'][32] = EnumEntry('MAV_MODE_FLAG_HIL_ENABLED', '''0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.''') +MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled. +enums['MAV_MODE_FLAG'][64] = EnumEntry('MAV_MODE_FLAG_MANUAL_INPUT_ENABLED', '''0b01000000 remote control input is enabled.''') +MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can + # start. Ready to fly. +enums['MAV_MODE_FLAG'][128] = EnumEntry('MAV_MODE_FLAG_SAFETY_ARMED', '''0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.''') +MAV_MODE_FLAG_ENUM_END = 129 # +enums['MAV_MODE_FLAG'][129] = EnumEntry('MAV_MODE_FLAG_ENUM_END', '''''') + +# MAV_MODE_FLAG_DECODE_POSITION +enums['MAV_MODE_FLAG_DECODE_POSITION'] = {} +MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001 +enums['MAV_MODE_FLAG_DECODE_POSITION'][1] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE', '''Eighth bit: 00000001''') +MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010 +enums['MAV_MODE_FLAG_DECODE_POSITION'][2] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_TEST', '''Seventh bit: 00000010''') +MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100 +enums['MAV_MODE_FLAG_DECODE_POSITION'][4] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_AUTO', '''Sixt bit: 00000100''') +MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][8] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_GUIDED', '''Fifth bit: 00001000''') +MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][16] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_STABILIZE', '''Fourth bit: 00010000''') +MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][32] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_HIL', '''Third bit: 00100000''') +MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][64] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_MANUAL', '''Second bit: 01000000''') +MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][128] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_SAFETY', '''First bit: 10000000''') +MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 # +enums['MAV_MODE_FLAG_DECODE_POSITION'][129] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_ENUM_END', '''''') + +# MAV_GOTO +enums['MAV_GOTO'] = {} +MAV_GOTO_DO_HOLD = 0 # Hold at the current position. +enums['MAV_GOTO'][0] = EnumEntry('MAV_GOTO_DO_HOLD', '''Hold at the current position.''') +MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution. +enums['MAV_GOTO'][1] = EnumEntry('MAV_GOTO_DO_CONTINUE', '''Continue with the next item in mission execution.''') +MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system +enums['MAV_GOTO'][2] = EnumEntry('MAV_GOTO_HOLD_AT_CURRENT_POSITION', '''Hold at the current position of the system''') +MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action +enums['MAV_GOTO'][3] = EnumEntry('MAV_GOTO_HOLD_AT_SPECIFIED_POSITION', '''Hold at the position specified in the parameters of the DO_HOLD action''') +MAV_GOTO_ENUM_END = 4 # +enums['MAV_GOTO'][4] = EnumEntry('MAV_GOTO_ENUM_END', '''''') + +# MAV_MODE +enums['MAV_MODE'] = {} +MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set. +enums['MAV_MODE'][0] = EnumEntry('MAV_MODE_PREFLIGHT', '''System is not ready to fly, booting, calibrating, etc. No flag is set.''') +MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][64] = EnumEntry('MAV_MODE_MANUAL_DISARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][66] = EnumEntry('MAV_MODE_TEST_DISARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][80] = EnumEntry('MAV_MODE_STABILIZE_DISARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][88] = EnumEntry('MAV_MODE_GUIDED_DISARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][92] = EnumEntry('MAV_MODE_AUTO_DISARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][192] = EnumEntry('MAV_MODE_MANUAL_ARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][194] = EnumEntry('MAV_MODE_TEST_ARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][208] = EnumEntry('MAV_MODE_STABILIZE_ARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][216] = EnumEntry('MAV_MODE_GUIDED_ARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][220] = EnumEntry('MAV_MODE_AUTO_ARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_ENUM_END = 221 # +enums['MAV_MODE'][221] = EnumEntry('MAV_MODE_ENUM_END', '''''') + +# MAV_STATE +enums['MAV_STATE'] = {} +MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown. +enums['MAV_STATE'][0] = EnumEntry('MAV_STATE_UNINIT', '''Uninitialized system, state is unknown.''') +MAV_STATE_BOOT = 1 # System is booting up. +enums['MAV_STATE'][1] = EnumEntry('MAV_STATE_BOOT', '''System is booting up.''') +MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready. +enums['MAV_STATE'][2] = EnumEntry('MAV_STATE_CALIBRATING', '''System is calibrating and not flight-ready.''') +MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time. +enums['MAV_STATE'][3] = EnumEntry('MAV_STATE_STANDBY', '''System is grounded and on standby. It can be launched any time.''') +MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged. +enums['MAV_STATE'][4] = EnumEntry('MAV_STATE_ACTIVE', '''System is active and might be already airborne. Motors are engaged.''') +MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate. +enums['MAV_STATE'][5] = EnumEntry('MAV_STATE_CRITICAL', '''System is in a non-normal flight mode. It can however still navigate.''') +MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or + # over the whole airframe. It is in mayday and + # going down. +enums['MAV_STATE'][6] = EnumEntry('MAV_STATE_EMERGENCY', '''System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.''') +MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now. +enums['MAV_STATE'][7] = EnumEntry('MAV_STATE_POWEROFF', '''System just initialized its power-down sequence, will shut down now.''') +MAV_STATE_ENUM_END = 8 # +enums['MAV_STATE'][8] = EnumEntry('MAV_STATE_ENUM_END', '''''') + +# MAV_COMPONENT +enums['MAV_COMPONENT'] = {} +MAV_COMP_ID_ALL = 0 # +enums['MAV_COMPONENT'][0] = EnumEntry('MAV_COMP_ID_ALL', '''''') +MAV_COMP_ID_CAMERA = 100 # +enums['MAV_COMPONENT'][100] = EnumEntry('MAV_COMP_ID_CAMERA', '''''') +MAV_COMP_ID_SERVO1 = 140 # +enums['MAV_COMPONENT'][140] = EnumEntry('MAV_COMP_ID_SERVO1', '''''') +MAV_COMP_ID_SERVO2 = 141 # +enums['MAV_COMPONENT'][141] = EnumEntry('MAV_COMP_ID_SERVO2', '''''') +MAV_COMP_ID_SERVO3 = 142 # +enums['MAV_COMPONENT'][142] = EnumEntry('MAV_COMP_ID_SERVO3', '''''') +MAV_COMP_ID_SERVO4 = 143 # +enums['MAV_COMPONENT'][143] = EnumEntry('MAV_COMP_ID_SERVO4', '''''') +MAV_COMP_ID_SERVO5 = 144 # +enums['MAV_COMPONENT'][144] = EnumEntry('MAV_COMP_ID_SERVO5', '''''') +MAV_COMP_ID_SERVO6 = 145 # +enums['MAV_COMPONENT'][145] = EnumEntry('MAV_COMP_ID_SERVO6', '''''') +MAV_COMP_ID_SERVO7 = 146 # +enums['MAV_COMPONENT'][146] = EnumEntry('MAV_COMP_ID_SERVO7', '''''') +MAV_COMP_ID_SERVO8 = 147 # +enums['MAV_COMPONENT'][147] = EnumEntry('MAV_COMP_ID_SERVO8', '''''') +MAV_COMP_ID_SERVO9 = 148 # +enums['MAV_COMPONENT'][148] = EnumEntry('MAV_COMP_ID_SERVO9', '''''') +MAV_COMP_ID_SERVO10 = 149 # +enums['MAV_COMPONENT'][149] = EnumEntry('MAV_COMP_ID_SERVO10', '''''') +MAV_COMP_ID_SERVO11 = 150 # +enums['MAV_COMPONENT'][150] = EnumEntry('MAV_COMP_ID_SERVO11', '''''') +MAV_COMP_ID_SERVO12 = 151 # +enums['MAV_COMPONENT'][151] = EnumEntry('MAV_COMP_ID_SERVO12', '''''') +MAV_COMP_ID_SERVO13 = 152 # +enums['MAV_COMPONENT'][152] = EnumEntry('MAV_COMP_ID_SERVO13', '''''') +MAV_COMP_ID_SERVO14 = 153 # +enums['MAV_COMPONENT'][153] = EnumEntry('MAV_COMP_ID_SERVO14', '''''') +MAV_COMP_ID_GIMBAL = 154 # +enums['MAV_COMPONENT'][154] = EnumEntry('MAV_COMP_ID_GIMBAL', '''''') +MAV_COMP_ID_LOG = 155 # +enums['MAV_COMPONENT'][155] = EnumEntry('MAV_COMP_ID_LOG', '''''') +MAV_COMP_ID_ADSB = 156 # +enums['MAV_COMPONENT'][156] = EnumEntry('MAV_COMP_ID_ADSB', '''''') +MAV_COMP_ID_OSD = 157 # On Screen Display (OSD) devices for video links +enums['MAV_COMPONENT'][157] = EnumEntry('MAV_COMP_ID_OSD', '''On Screen Display (OSD) devices for video links''') +MAV_COMP_ID_PERIPHERAL = 158 # Generic autopilot peripheral component ID. Meant for devices that do + # not implement the parameter sub-protocol +enums['MAV_COMPONENT'][158] = EnumEntry('MAV_COMP_ID_PERIPHERAL', '''Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol''') +MAV_COMP_ID_MAPPER = 180 # +enums['MAV_COMPONENT'][180] = EnumEntry('MAV_COMP_ID_MAPPER', '''''') +MAV_COMP_ID_MISSIONPLANNER = 190 # +enums['MAV_COMPONENT'][190] = EnumEntry('MAV_COMP_ID_MISSIONPLANNER', '''''') +MAV_COMP_ID_PATHPLANNER = 195 # +enums['MAV_COMPONENT'][195] = EnumEntry('MAV_COMP_ID_PATHPLANNER', '''''') +MAV_COMP_ID_IMU = 200 # +enums['MAV_COMPONENT'][200] = EnumEntry('MAV_COMP_ID_IMU', '''''') +MAV_COMP_ID_IMU_2 = 201 # +enums['MAV_COMPONENT'][201] = EnumEntry('MAV_COMP_ID_IMU_2', '''''') +MAV_COMP_ID_IMU_3 = 202 # +enums['MAV_COMPONENT'][202] = EnumEntry('MAV_COMP_ID_IMU_3', '''''') +MAV_COMP_ID_GPS = 220 # +enums['MAV_COMPONENT'][220] = EnumEntry('MAV_COMP_ID_GPS', '''''') +MAV_COMP_ID_UDP_BRIDGE = 240 # +enums['MAV_COMPONENT'][240] = EnumEntry('MAV_COMP_ID_UDP_BRIDGE', '''''') +MAV_COMP_ID_UART_BRIDGE = 241 # +enums['MAV_COMPONENT'][241] = EnumEntry('MAV_COMP_ID_UART_BRIDGE', '''''') +MAV_COMP_ID_SYSTEM_CONTROL = 250 # +enums['MAV_COMPONENT'][250] = EnumEntry('MAV_COMP_ID_SYSTEM_CONTROL', '''''') +MAV_COMPONENT_ENUM_END = 251 # +enums['MAV_COMPONENT'][251] = EnumEntry('MAV_COMPONENT_ENUM_END', '''''') + +# MAV_SYS_STATUS_SENSOR +enums['MAV_SYS_STATUS_SENSOR'] = {} +MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 # 0x01 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][1] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO', '''0x01 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 # 0x02 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][2] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL', '''0x02 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG = 4 # 0x04 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][4] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG', '''0x04 3D magnetometer''') +MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 # 0x08 absolute pressure +enums['MAV_SYS_STATUS_SENSOR'][8] = EnumEntry('MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE', '''0x08 absolute pressure''') +MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 # 0x10 differential pressure +enums['MAV_SYS_STATUS_SENSOR'][16] = EnumEntry('MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE', '''0x10 differential pressure''') +MAV_SYS_STATUS_SENSOR_GPS = 32 # 0x20 GPS +enums['MAV_SYS_STATUS_SENSOR'][32] = EnumEntry('MAV_SYS_STATUS_SENSOR_GPS', '''0x20 GPS''') +MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 # 0x40 optical flow +enums['MAV_SYS_STATUS_SENSOR'][64] = EnumEntry('MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW', '''0x40 optical flow''') +MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 # 0x80 computer vision position +enums['MAV_SYS_STATUS_SENSOR'][128] = EnumEntry('MAV_SYS_STATUS_SENSOR_VISION_POSITION', '''0x80 computer vision position''') +MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 # 0x100 laser based position +enums['MAV_SYS_STATUS_SENSOR'][256] = EnumEntry('MAV_SYS_STATUS_SENSOR_LASER_POSITION', '''0x100 laser based position''') +MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 # 0x200 external ground truth (Vicon or Leica) +enums['MAV_SYS_STATUS_SENSOR'][512] = EnumEntry('MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH', '''0x200 external ground truth (Vicon or Leica)''') +MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 # 0x400 3D angular rate control +enums['MAV_SYS_STATUS_SENSOR'][1024] = EnumEntry('MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL', '''0x400 3D angular rate control''') +MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 # 0x800 attitude stabilization +enums['MAV_SYS_STATUS_SENSOR'][2048] = EnumEntry('MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION', '''0x800 attitude stabilization''') +MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 # 0x1000 yaw position +enums['MAV_SYS_STATUS_SENSOR'][4096] = EnumEntry('MAV_SYS_STATUS_SENSOR_YAW_POSITION', '''0x1000 yaw position''') +MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 # 0x2000 z/altitude control +enums['MAV_SYS_STATUS_SENSOR'][8192] = EnumEntry('MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL', '''0x2000 z/altitude control''') +MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 # 0x4000 x/y position control +enums['MAV_SYS_STATUS_SENSOR'][16384] = EnumEntry('MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL', '''0x4000 x/y position control''') +MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 # 0x8000 motor outputs / control +enums['MAV_SYS_STATUS_SENSOR'][32768] = EnumEntry('MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS', '''0x8000 motor outputs / control''') +MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 # 0x10000 rc receiver +enums['MAV_SYS_STATUS_SENSOR'][65536] = EnumEntry('MAV_SYS_STATUS_SENSOR_RC_RECEIVER', '''0x10000 rc receiver''') +MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 # 0x20000 2nd 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][131072] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO2', '''0x20000 2nd 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 # 0x40000 2nd 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][262144] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL2', '''0x40000 2nd 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 # 0x80000 2nd 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][524288] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG2', '''0x80000 2nd 3D magnetometer''') +MAV_SYS_STATUS_GEOFENCE = 1048576 # 0x100000 geofence +enums['MAV_SYS_STATUS_SENSOR'][1048576] = EnumEntry('MAV_SYS_STATUS_GEOFENCE', '''0x100000 geofence''') +MAV_SYS_STATUS_AHRS = 2097152 # 0x200000 AHRS subsystem health +enums['MAV_SYS_STATUS_SENSOR'][2097152] = EnumEntry('MAV_SYS_STATUS_AHRS', '''0x200000 AHRS subsystem health''') +MAV_SYS_STATUS_TERRAIN = 4194304 # 0x400000 Terrain subsystem health +enums['MAV_SYS_STATUS_SENSOR'][4194304] = EnumEntry('MAV_SYS_STATUS_TERRAIN', '''0x400000 Terrain subsystem health''') +MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 # 0x800000 Motors are reversed +enums['MAV_SYS_STATUS_SENSOR'][8388608] = EnumEntry('MAV_SYS_STATUS_REVERSE_MOTOR', '''0x800000 Motors are reversed''') +MAV_SYS_STATUS_SENSOR_ENUM_END = 8388609 # +enums['MAV_SYS_STATUS_SENSOR'][8388609] = EnumEntry('MAV_SYS_STATUS_SENSOR_ENUM_END', '''''') + +# MAV_FRAME +enums['MAV_FRAME'] = {} +MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude, second value / y: longitude, third + # value / z: positive altitude over mean sea + # level (MSL) +enums['MAV_FRAME'][0] = EnumEntry('MAV_FRAME_GLOBAL', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down). +enums['MAV_FRAME'][1] = EnumEntry('MAV_FRAME_LOCAL_NED', '''Local coordinate frame, Z-up (x: north, y: east, z: down).''') +MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command. +enums['MAV_FRAME'][2] = EnumEntry('MAV_FRAME_MISSION', '''NOT a coordinate frame, indicates a mission command.''') +MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude, second + # value / y: longitude, third value / z: + # positive altitude with 0 being at the + # altitude of the home location. +enums['MAV_FRAME'][3] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up) +enums['MAV_FRAME'][4] = EnumEntry('MAV_FRAME_LOCAL_ENU', '''Local coordinate frame, Z-down (x: east, y: north, z: up)''') +MAV_FRAME_GLOBAL_INT = 5 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude in degrees*1.0e-7, second value / + # y: longitude in degrees*1.0e-7, third value + # / z: positive altitude over mean sea level + # (MSL) +enums['MAV_FRAME'][5] = EnumEntry('MAV_FRAME_GLOBAL_INT', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude with 0 being at the altitude of the + # home location. +enums['MAV_FRAME'][6] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT_INT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame + # should be added to the current local frame + # position. +enums['MAV_FRAME'][7] = EnumEntry('MAV_FRAME_LOCAL_OFFSET_NED', '''Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.''') +MAV_FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control + # is externalized - e.g. useful to command 2 + # m/s^2 acceleration to the right. +enums['MAV_FRAME'][8] = EnumEntry('MAV_FRAME_BODY_NED', '''Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.''') +MAV_FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the + # current flight path, to avoid an obstacle - + # e.g. useful to command 2 m/s^2 acceleration + # to the east. +enums['MAV_FRAME'][9] = EnumEntry('MAV_FRAME_BODY_OFFSET_NED', '''Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees, second value / y: longitude in + # degrees, third value / z: positive altitude + # in meters with 0 being at ground level in + # terrain model. +enums['MAV_FRAME'][10] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude in meters with 0 being at ground + # level in terrain model. +enums['MAV_FRAME'][11] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT_INT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_ENUM_END = 12 # +enums['MAV_FRAME'][12] = EnumEntry('MAV_FRAME_ENUM_END', '''''') + +# MAVLINK_DATA_STREAM_TYPE +enums['MAVLINK_DATA_STREAM_TYPE'] = {} +MAVLINK_DATA_STREAM_IMG_JPEG = 1 # +enums['MAVLINK_DATA_STREAM_TYPE'][1] = EnumEntry('MAVLINK_DATA_STREAM_IMG_JPEG', '''''') +MAVLINK_DATA_STREAM_IMG_BMP = 2 # +enums['MAVLINK_DATA_STREAM_TYPE'][2] = EnumEntry('MAVLINK_DATA_STREAM_IMG_BMP', '''''') +MAVLINK_DATA_STREAM_IMG_RAW8U = 3 # +enums['MAVLINK_DATA_STREAM_TYPE'][3] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW8U', '''''') +MAVLINK_DATA_STREAM_IMG_RAW32U = 4 # +enums['MAVLINK_DATA_STREAM_TYPE'][4] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW32U', '''''') +MAVLINK_DATA_STREAM_IMG_PGM = 5 # +enums['MAVLINK_DATA_STREAM_TYPE'][5] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PGM', '''''') +MAVLINK_DATA_STREAM_IMG_PNG = 6 # +enums['MAVLINK_DATA_STREAM_TYPE'][6] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PNG', '''''') +MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 # +enums['MAVLINK_DATA_STREAM_TYPE'][7] = EnumEntry('MAVLINK_DATA_STREAM_TYPE_ENUM_END', '''''') + +# FENCE_ACTION +enums['FENCE_ACTION'] = {} +FENCE_ACTION_NONE = 0 # Disable fenced mode +enums['FENCE_ACTION'][0] = EnumEntry('FENCE_ACTION_NONE', '''Disable fenced mode''') +FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0) +enums['FENCE_ACTION'][1] = EnumEntry('FENCE_ACTION_GUIDED', '''Switched to guided mode to return point (fence point 0)''') +FENCE_ACTION_REPORT = 2 # Report fence breach, but don't take action +enums['FENCE_ACTION'][2] = EnumEntry('FENCE_ACTION_REPORT', '''Report fence breach, but don't take action''') +FENCE_ACTION_GUIDED_THR_PASS = 3 # Switched to guided mode to return point (fence point 0) with manual + # throttle control +enums['FENCE_ACTION'][3] = EnumEntry('FENCE_ACTION_GUIDED_THR_PASS', '''Switched to guided mode to return point (fence point 0) with manual throttle control''') +FENCE_ACTION_ENUM_END = 4 # +enums['FENCE_ACTION'][4] = EnumEntry('FENCE_ACTION_ENUM_END', '''''') + +# FENCE_BREACH +enums['FENCE_BREACH'] = {} +FENCE_BREACH_NONE = 0 # No last fence breach +enums['FENCE_BREACH'][0] = EnumEntry('FENCE_BREACH_NONE', '''No last fence breach''') +FENCE_BREACH_MINALT = 1 # Breached minimum altitude +enums['FENCE_BREACH'][1] = EnumEntry('FENCE_BREACH_MINALT', '''Breached minimum altitude''') +FENCE_BREACH_MAXALT = 2 # Breached maximum altitude +enums['FENCE_BREACH'][2] = EnumEntry('FENCE_BREACH_MAXALT', '''Breached maximum altitude''') +FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary +enums['FENCE_BREACH'][3] = EnumEntry('FENCE_BREACH_BOUNDARY', '''Breached fence boundary''') +FENCE_BREACH_ENUM_END = 4 # +enums['FENCE_BREACH'][4] = EnumEntry('FENCE_BREACH_ENUM_END', '''''') + +# MAV_MOUNT_MODE +enums['MAV_MOUNT_MODE'] = {} +MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permant memory and + # stop stabilization +enums['MAV_MOUNT_MODE'][0] = EnumEntry('MAV_MOUNT_MODE_RETRACT', '''Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization''') +MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +enums['MAV_MOUNT_MODE'][1] = EnumEntry('MAV_MOUNT_MODE_NEUTRAL', '''Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.''') +MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][2] = EnumEntry('MAV_MOUNT_MODE_MAVLINK_TARGETING', '''Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][3] = EnumEntry('MAV_MOUNT_MODE_RC_TARGETING', '''Load neutral position and start RC Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt +enums['MAV_MOUNT_MODE'][4] = EnumEntry('MAV_MOUNT_MODE_GPS_POINT', '''Load neutral position and start to point to Lat,Lon,Alt''') +MAV_MOUNT_MODE_ENUM_END = 5 # +enums['MAV_MOUNT_MODE'][5] = EnumEntry('MAV_MOUNT_MODE_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_AQ_TELEMETRY_F = 150 +MAVLINK_MSG_ID_AQ_ESC_TELEMETRY = 152 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_aq_telemetry_f_message(MAVLink_message): + ''' + Sends up to 20 raw float values. + ''' + id = MAVLINK_MSG_ID_AQ_TELEMETRY_F + name = 'AQ_TELEMETRY_F' + fieldnames = ['Index', 'value1', 'value2', 'value3', 'value4', 'value5', 'value6', 'value7', 'value8', 'value9', 'value10', 'value11', 'value12', 'value13', 'value14', 'value15', 'value16', 'value17', 'value18', 'value19', 'value20'] + ordered_fieldnames = [ 'value1', 'value2', 'value3', 'value4', 'value5', 'value6', 'value7', 'value8', 'value9', 'value10', 'value11', 'value12', 'value13', 'value14', 'value15', 'value16', 'value17', 'value18', 'value19', 'value20', 'Index' ] + format = ' 4 motors. + Data is described as follows: + // unsigned int state : 3; // + unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - // + unsigned int errors : 9; // Bad detects error count + // - Data Version 3 - // + unsigned int temp : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + ''' + id = MAVLINK_MSG_ID_AQ_ESC_TELEMETRY + name = 'AQ_ESC_TELEMETRY' + fieldnames = ['time_boot_ms', 'seq', 'num_motors', 'num_in_seq', 'escid', 'status_age', 'data_version', 'data0', 'data1'] + ordered_fieldnames = [ 'time_boot_ms', 'data0', 'data1', 'status_age', 'seq', 'num_motors', 'num_in_seq', 'escid', 'data_version' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' 4 motors. Data + is described as follows: + // unsigned int state : 3; + // unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - // + unsigned int errors : 9; // Bad detects error + count // - Data Version 3 + - // unsigned int temp + : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + + time_boot_ms : Timestamp of the component clock since boot time in ms. (uint32_t) + seq : Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc). (uint8_t) + num_motors : Total number of active ESCs/motors on the system. (uint8_t) + num_in_seq : Number of active ESCs in this sequence (1 through this many array members will be populated with data) (uint8_t) + escid : ESC/Motor ID (uint8_t) + status_age : Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data. (uint16_t) + data_version : Version of data structure (determines contents). (uint8_t) + data0 : Data bits 1-32 for each ESC. (uint32_t) + data1 : Data bits 33-64 for each ESC. (uint32_t) + + ''' + return MAVLink_aq_esc_telemetry_message(time_boot_ms, seq, num_motors, num_in_seq, escid, status_age, data_version, data0, data1) + + def aq_esc_telemetry_send(self, time_boot_ms, seq, num_motors, num_in_seq, escid, status_age, data_version, data0, data1): + ''' + Sends ESC32 telemetry data for up to 4 motors. Multiple messages may + be sent in sequence when system has > 4 motors. Data + is described as follows: + // unsigned int state : 3; + // unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - // + unsigned int errors : 9; // Bad detects error + count // - Data Version 3 + - // unsigned int temp + : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + + time_boot_ms : Timestamp of the component clock since boot time in ms. (uint32_t) + seq : Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc). (uint8_t) + num_motors : Total number of active ESCs/motors on the system. (uint8_t) + num_in_seq : Number of active ESCs in this sequence (1 through this many array members will be populated with data) (uint8_t) + escid : ESC/Motor ID (uint8_t) + status_age : Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data. (uint16_t) + data_version : Version of data structure (determines contents). (uint8_t) + data0 : Data bits 1-32 for each ESC. (uint32_t) + data1 : Data bits 33-64 for each ESC. (uint32_t) + + ''' + return self.send(self.aq_esc_telemetry_encode(time_boot_ms, seq, num_motors, num_in_seq, escid, status_age, data_version, data0, data1)) + + def heartbeat_encode(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): + ''' + The heartbeat message shows that a system is present and responding. + The type of the MAV and Autopilot hardware allow the + receiving system to treat further messages from this + system appropriate (e.g. by laying out the user + interface based on the autopilot). + + type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) + autopilot : Autopilot type / class. defined in MAV_AUTOPILOT ENUM (uint8_t) + base_mode : System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h (uint8_t) + custom_mode : A bitfield for use for autopilot-specific flags. (uint32_t) + system_status : System status flag, see MAV_STATE ENUM (uint8_t) + mavlink_version : MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version (uint8_t) + + ''' + return MAVLink_heartbeat_message(type, autopilot, base_mode, custom_mode, system_status, mavlink_version) + + def heartbeat_send(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): + ''' + The heartbeat message shows that a system is present and responding. + The type of the MAV and Autopilot hardware allow the + receiving system to treat further messages from this + system appropriate (e.g. by laying out the user + interface based on the autopilot). + + type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) + autopilot : Autopilot type / class. defined in MAV_AUTOPILOT ENUM (uint8_t) + base_mode : System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h (uint8_t) + custom_mode : A bitfield for use for autopilot-specific flags. (uint32_t) + system_status : System status flag, see MAV_STATE ENUM (uint8_t) + mavlink_version : MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version (uint8_t) + + ''' + return self.send(self.heartbeat_encode(type, autopilot, base_mode, custom_mode, system_status, mavlink_version)) + + def sys_status_encode(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) + drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_count1 : Autopilot-specific errors (uint16_t) + errors_count2 : Autopilot-specific errors (uint16_t) + errors_count3 : Autopilot-specific errors (uint16_t) + errors_count4 : Autopilot-specific errors (uint16_t) + + ''' + return MAVLink_sys_status_message(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4) + + def sys_status_send(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): + ''' + The general system state. If the system is following the MAVLink + standard, the system state is mainly defined by three + orthogonal states/modes: The system mode, which is + either LOCKED (motors shut down and locked), MANUAL + (system under RC control), GUIDED (system with + autonomous position control, position setpoint + controlled manually) or AUTO (system guided by + path/waypoint planner). The NAV_MODE defined the + current flight state: LIFTOFF (often an open-loop + maneuver), LANDING, WAYPOINTS or VECTOR. This + represents the internal navigation state machine. The + system status shows wether the system is currently + active or not and if an emergency occured. During the + CRITICAL and EMERGENCY states the MAV is still + considered to be active, but should start emergency + procedures autonomously. After a failure occured it + should first move from active to critical to allow + manual intervention and then move to emergency after a + certain timeout. + + onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR (uint32_t) + load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) + voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) + drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) + errors_count1 : Autopilot-specific errors (uint16_t) + errors_count2 : Autopilot-specific errors (uint16_t) + errors_count3 : Autopilot-specific errors (uint16_t) + errors_count4 : Autopilot-specific errors (uint16_t) + + ''' + return self.send(self.sys_status_encode(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4)) + + def system_time_encode(self, time_unix_usec, time_boot_ms): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + + time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) + time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) + + ''' + return MAVLink_system_time_message(time_unix_usec, time_boot_ms) + + def system_time_send(self, time_unix_usec, time_boot_ms): + ''' + The system time is the time of the master clock, typically the + computer clock of the main onboard computer. + + time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) + time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) + + ''' + return self.send(self.system_time_encode(time_unix_usec, time_boot_ms)) + + def ping_encode(self, time_usec, seq, target_system, target_component): + ''' + A ping message either requesting or responding to a ping. This allows + to measure the system latencies, including serial + port, radio modem and UDP connections. + + time_usec : Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) (uint64_t) + seq : PING sequence (uint32_t) + target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + + ''' + return MAVLink_ping_message(time_usec, seq, target_system, target_component) + + def ping_send(self, time_usec, seq, target_system, target_component): + ''' + A ping message either requesting or responding to a ping. This allows + to measure the system latencies, including serial + port, radio modem and UDP connections. + + time_usec : Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) (uint64_t) + seq : PING sequence (uint32_t) + target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) + + ''' + return self.send(self.ping_encode(time_usec, seq, target_system, target_component)) + + def change_operator_control_encode(self, target_system, control_request, version, passkey): + ''' + Request to control this MAV + + target_system : System the GCS requests control for (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) + passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) + + ''' + return MAVLink_change_operator_control_message(target_system, control_request, version, passkey) + + def change_operator_control_send(self, target_system, control_request, version, passkey): + ''' + Request to control this MAV + + target_system : System the GCS requests control for (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) + passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) + + ''' + return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) + + def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): + ''' + Accept / deny control of this MAV + + gcs_system_id : ID of the GCS this message (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) + + ''' + return MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) + + def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): + ''' + Accept / deny control of this MAV + + gcs_system_id : ID of the GCS this message (uint8_t) + control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) + ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) + + ''' + return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) + + def auth_key_encode(self, key): + ''' + Emit an encrypted signature / key identifying this system. PLEASE + NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for + true safety. + + key : key (char) + + ''' + return MAVLink_auth_key_message(key) + + def auth_key_send(self, key): + ''' + Emit an encrypted signature / key identifying this system. PLEASE + NOTE: This protocol has been kept simple, so + transmitting the key requires an encrypted channel for + true safety. + + key : key (char) + + ''' + return self.send(self.auth_key_encode(key)) + + def set_mode_encode(self, target_system, base_mode, custom_mode): + ''' + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with + MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as + defined by enum MAV_MODE. There is no target component + id as the mode is by definition for the overall + aircraft, not only for one component. + + target_system : The system setting the mode (uint8_t) + base_mode : The new base mode (uint8_t) + custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) + + ''' + return MAVLink_set_mode_message(target_system, base_mode, custom_mode) + + def set_mode_send(self, target_system, base_mode, custom_mode): + ''' + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with + MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as + defined by enum MAV_MODE. There is no target component + id as the mode is by definition for the overall + aircraft, not only for one component. + + target_system : The system setting the mode (uint8_t) + base_mode : The new base mode (uint8_t) + custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) + + ''' + return self.send(self.set_mode_encode(target_system, base_mode, custom_mode)) + + def param_request_read_encode(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/autoquad.xml b/pymavlink/dialects/v10/autoquad.xml new file mode 100644 index 0000000..8c22478 --- /dev/null +++ b/pymavlink/dialects/v10/autoquad.xml @@ -0,0 +1,169 @@ + + + common.xml + 3 + + + Track current version of these definitions (can be used by checking value of AUTOQUAD_MAVLINK_DEFS_VERSION_ENUM_END). Append a new entry for each published change. + + + + Available operating modes/statuses for AutoQuad flight controller. + Bitmask up to 32 bits. Low side bits for base modes, high side for + additional active features/modifiers/constraints. + + System is initializing + + + + System is *armed* and standing by, with no throttle input and no autonomous mode + + + Flying (throttle input detected), assumed under manual control unless other mode bits are set + + + Altitude hold engaged + + + Position hold engaged + + + Externally-guided (eg. GCS) navigation mode + + + Autonomous mission execution mode + + + + Ready but *not armed* + + + Calibration mode active + + + + No valid control input (eg. no radio link) + + + Battery is low (stage 1 warning) + + + Battery is depleted (stage 2 warning) + + + + Dynamic Velocity Hold is active (PH with proportional manual direction override) + + + ynamic Altitude Override is active (AH with proportional manual adjustment) + + + + Craft is at ceiling altitude + + + Ceiling altitude is set + + + Heading-Free dynamic mode active + + + Heading-Free locked mode active + + + Automatic Return to Home is active + + + System is in failsafe recovery mode + + + + + Orbit a waypoint. + Orbit radius in meters + Loiter time in decimal seconds + Maximum horizontal speed in m/s + Desired yaw angle at waypoint + Latitude + Longitude + Altitude + + + Start/stop AutoQuad telemetry values stream. + Start or stop (1 or 0) + Stream frequency in us + Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code) + Empty + Empty + Empty + Empty + + + + Request AutoQuad firmware version number. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + + Motor/ESC telemetry data. + + + + + + Sends up to 20 raw float values. + Index of message + value1 + value2 + value3 + value4 + value5 + value6 + value7 + value8 + value9 + value10 + value11 + value12 + value13 + value14 + value15 + value16 + value17 + value18 + value19 + value20 + + + Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has > 4 motors. Data is described as follows: + // unsigned int state : 3; + // unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - + // unsigned int errors : 9; // Bad detects error count + // - Data Version 3 - + // unsigned int temp : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + + Timestamp of the component clock since boot time in ms. + Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc). + Total number of active ESCs/motors on the system. + Number of active ESCs in this sequence (1 through this many array members will be populated with data) + ESC/Motor ID + Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data. + Version of data structure (determines contents). + Data bits 1-32 for each ESC. + Data bits 33-64 for each ESC. + + + diff --git a/pymavlink/dialects/v10/common.py b/pymavlink/dialects/v10/common.py new file mode 100644 index 0000000..5c386fb --- /dev/null +++ b/pymavlink/dialects/v10/common.py @@ -0,0 +1,10942 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "common" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_heartbeat_message(MAVLink_message): + ''' + The heartbeat message shows that a system is present and + responding. The type of the MAV and Autopilot hardware allow + the receiving system to treat further messages from this + system appropriate (e.g. by laying out the user interface + based on the autopilot). + ''' + id = MAVLINK_MSG_ID_HEARTBEAT + name = 'HEARTBEAT' + fieldnames = ['type', 'autopilot', 'base_mode', 'custom_mode', 'system_status', 'mavlink_version'] + ordered_fieldnames = [ 'custom_mode', 'type', 'autopilot', 'base_mode', 'system_status', 'mavlink_version' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/common.xml b/pymavlink/dialects/v10/common.xml new file mode 100644 index 0000000..a055de9 --- /dev/null +++ b/pymavlink/dialects/v10/common.xml @@ -0,0 +1,3347 @@ + + + 3 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + Reserved for future use. + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + PX4 Autopilot - http://pixhawk.ethz.ch/px4/ + + + SMACCMPilot - http://smaccmpilot.org + + + AutoQuad -- http://autoquad.org + + + Armazila -- http://armazila.com + + + Aerob -- http://aerob.ru + + + ASLUAV autopilot -- http://www.asl.ethz.ch + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + Flapping wing + + + Onboard companion controller + + + Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. + + + Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. + + + Tiltrotor VTOL + + + + VTOL reserved 2 + + + VTOL reserved 3 + + + VTOL reserved 4 + + + VTOL reserved 5 + + + Onboard gimbal + + + Onboard ADSB peripheral + + + + These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. + + development release + + + alpha release + + + beta release + + + release candidate + + + official stable release + + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + Override command, pauses current mission execution and moves immediately to a position + + Hold at the current position. + + + Continue with the next item in mission execution. + + + Hold at the current position of the system + + + Hold at the position specified in the parameters of the DO_HOLD action + + + + These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. + + System is not ready to fly, booting, calibrating, etc. No flag is set. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + On Screen Display (OSD) devices for video links + + + Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol + + + + These encode the sensors whose status is sent as part of the SYS_STATUS message. + + 0x01 3D gyro + + + 0x02 3D accelerometer + + + 0x04 3D magnetometer + + + 0x08 absolute pressure + + + 0x10 differential pressure + + + 0x20 GPS + + + 0x40 optical flow + + + 0x80 computer vision position + + + 0x100 laser based position + + + 0x200 external ground truth (Vicon or Leica) + + + 0x400 3D angular rate control + + + 0x800 attitude stabilization + + + 0x1000 yaw position + + + 0x2000 z/altitude control + + + 0x4000 x/y position control + + + 0x8000 motor outputs / control + + + 0x10000 rc receiver + + + 0x20000 2nd 3D gyro + + + 0x40000 2nd 3D accelerometer + + + 0x80000 2nd 3D magnetometer + + + 0x100000 geofence + + + 0x200000 AHRS subsystem health + + + 0x400000 Terrain subsystem health + + + 0x800000 Motors are reversed + + + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) + + + Local coordinate frame, Z-up (x: north, y: east, z: down). + + + NOT a coordinate frame, indicates a mission command. + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Local coordinate frame, Z-down (x: east, y: north, z: up) + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. + + + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + + + Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + + + + + + + + + + + + + + + + + + + + + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + Report fence breach, but don't take action + + + Switched to guided mode to return point (fence point 0) with manual throttle control + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached maximum altitude + + + Breached fence boundary + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + + + Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to MISSION. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at MISSION (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this MISSION an unlimited amount of time + Empty + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X turns + Turns + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X seconds + Seconds (decimal) + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Abort Alt + Empty + Empty + Desired yaw angle + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Land at local position (local frame only) + Landing target number (if available) + Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land + Landing descend rate [ms^-1] + Desired yaw angle [rad] + Y-axis position [m] + X-axis position [m] + Z-axis / ground level position [m] + + + Takeoff from local position (local frame only) + Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad] + Empty + Takeoff ascend rate [ms^-1] + Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these + Y-axis position [m] + X-axis position [m] + Z-axis position [m] + + + Vehicle following, i.e. this waypoint represents the position of a moving vehicle + Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation + Ground speed of vehicle to be followed + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. + Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. + Empty + Empty + Empty + Empty + Empty + Desired altitude in meters + + + Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. + Heading Required (0 = False) + Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. + Empty + Empty + Latitude + Longitude + Altitude + + + Being following a target + System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode + RESERVED + RESERVED + altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home + altitude + RESERVED + TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout + + + Reposition the MAV after a follow target command has been sent + Camera q1 (where 0 is on the ray from the camera to the tracking device) + Camera q2 + Camera q3 + Camera q4 + altitude offset from target (m) + X offset from target (m) + Y offset from target (m) + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Navigate to MISSION using a spline path. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Empty + Empty + Empty + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Takeoff from ground using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + Land using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + + + + hand control over to an external controller + On / Off (> 0.5f on) + Empty + Empty + Empty + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Custom mode - this is system specific, please refer to the individual autopilot specifications for details. + Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + Empty + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Terminate flight immediately + Flight termination activated if > 0.5 + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. + Empty + Empty + Empty + Empty + Latitude + Longitude + Empty + + + Mission command to perform a landing from a rally point. + Break altitude (meters) + Landing speed (m/s) + Empty + Empty + Empty + Empty + Empty + + + Mission command to safely abort an autonmous landing. + Altitude (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reposition the vehicle to a specific WGS84 global position. + Ground speed, less than 0 (-1) for default + Reserved + Reserved + Yaw heading, NaN for unchanged + Latitude (deg * 1E7) + Longitude (deg * 1E7) + Altitude (meters) + + + If in a GPS controlled position mode, hold the current position or continue. + 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Control onboard camera system. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch or lat in degrees, depending on mount mode. + roll or lon in degrees depending on mount mode + yaw or alt (in meters) depending on mount mode + reserved + reserved + reserved + MAV_MOUNT_MODE enum value + + + + Mission command to set CAM_TRIGG_DIST for this flight + Camera trigger distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to enable the geofence + enable? (0=disable, 1=enable, 2=disable_floor_only) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to trigger a parachute + action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Change to/from inverted flight + inverted (0=normal, 1=inverted) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount, using a quaternion as reference. + q1 - quaternion param #1, w (1 in null-rotation) + q2 - quaternion param #2, x (0 in null-rotation) + q3 - quaternion param #3, y (0 in null-rotation) + q4 - quaternion param #4, z (0 in null-rotation) + Empty + Empty + Empty + + + + set id of master controller + System ID + Component ID + Empty + Empty + Empty + Empty + Empty + + + + set limits for external control + timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout + absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit + absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit + horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit + Empty + Empty + Empty + + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Accelerometer calibration: 0: no, 1: yes + Compass/Motor interference calibration: 0: no, 1: yes + Empty + + + Set sensor offsets. This command will be only accepted if in pre-flight mode. + Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer + X axis offset (or generic dimension 1), in the sensor's raw units + Y axis offset (or generic dimension 2), in the sensor's raw units + Z axis offset (or generic dimension 3), in the sensor's raw units + Generic dimension 4, in the sensor's raw units + Generic dimension 5, in the sensor's raw units + Generic dimension 6, in the sensor's raw units + + + Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. + 1: Trigger actuator ID assignment and direction mapping. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging) + Reserved + Empty + Empty + Empty + + + Request the reboot or shutdown of system components. + 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. + 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + + + Hold / continue the current action + MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan + MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position + MAV_FRAME coordinate frame of hold point + Desired yaw angle in degrees + Latitude / X position + Longitude / Y position + Altitude / Z position + + + start running a mission + first_item: the first mission item to run + last_item: the last mission item to run (after this item is run, the mission ends) + + + Arms / Disarms a component + 1 to arm, 0 to disarm + + + Request the home position from the vehicle. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Starts receiver pairing + 0:Spektrum + 0:Spektrum DSM2, 1:Spektrum DSMX + + + Request the interval between messages for a particular MAVLink message ID + The MAVLink message ID + + + Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM + The MAVLink message ID + The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate. + + + Request autopilot capabilities + 1: Request autopilot version + Reserved (all remaining params) + + + Start image capture sequence + Duration between two consecutive pictures (in seconds) + Number of images to capture total - 0 for unlimited capture + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop image capture sequence + Reserved + Reserved + + + + Enable or disable on-board camera triggering system. + Trigger enable/disable (0 for disable, 1 for start) + Shutter integration time (in ms) + Reserved + + + + Starts video capture + Camera ID (0 for all cameras), 1 for first, 2 for second, etc. + Frames per second + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop the current video capture + Reserved + Reserved + + + + Create a panorama at the current position + Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle) + Viewing angle vertical of panorama (in degrees) + Speed of the horizontal rotation (in degrees per second) + Speed of the vertical rotation (in degrees per second) + + + + Request VTOL transition + The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. + + + + + + + Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. + Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. + Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. + Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. + Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. + Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Altitude, in meters AMSL + + + Control the payload deployment. + Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + + + THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + No region of interest. + + + Point toward next MISSION. + + + Point toward given MISSION. + + + Point toward fixed location. + + + Point toward of given id. + + + + ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. + + Command / mission item is ok. + + + Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. + + + The system is refusing to accept this command from this source / communication partner. + + + Command or mission item is not supported, other commands would be accepted. + + + The coordinate frame of this command / mission item is not supported. + + + 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. + + + The X or latitude value is out of range. + + + The Y or longitude value is out of range. + + + The Z or altitude value is out of range. + + + + Specifies the datatype of a MAVLink parameter. + + 8-bit unsigned integer + + + 8-bit signed integer + + + 16-bit unsigned integer + + + 16-bit signed integer + + + 32-bit unsigned integer + + + 32-bit signed integer + + + 64-bit unsigned integer + + + 64-bit signed integer + + + 32-bit floating-point + + + 64-bit floating-point + + + + result from a mavlink command + + Command ACCEPTED and EXECUTED + + + Command TEMPORARY REJECTED/DENIED + + + Command PERMANENTLY DENIED + + + Command UNKNOWN/UNSUPPORTED + + + Command executed, but failed + + + + result in a mavlink mission ack + + mission accepted OK + + + generic error / not accepting mission commands at all right now + + + coordinate frame is not supported + + + command is not supported + + + mission item exceeds storage space + + + one of the parameters has an invalid value + + + param1 has an invalid value + + + param2 has an invalid value + + + param3 has an invalid value + + + param4 has an invalid value + + + x/param5 has an invalid value + + + y/param6 has an invalid value + + + param7 has an invalid value + + + received waypoint out of sequence + + + not accepting any mission commands from this communication partner + + + + Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. + + System is unusable. This is a "panic" condition. + + + Action should be taken immediately. Indicates error in non-critical systems. + + + Action must be taken immediately. Indicates failure in a primary system. + + + Indicates an error in secondary/redundant systems. + + + Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. + + + An unusual event has occured, though not an error condition. This should be investigated for the root cause. + + + Normal operational messages. Useful for logging. No action is required for these messages. + + + Useful non-operational messages that can assist in debugging. These should not occur during normal operation. + + + + Power supply status flags (bitmask) + + main brick power supply valid + + + main servo power supply valid for FMU + + + USB power is connected + + + peripheral supply is in over-current state + + + hi-power peripheral supply is in over-current state + + + Power status has changed since boot + + + + SERIAL_CONTROL device types + + First telemetry port + + + Second telemetry port + + + First GPS port + + + Second GPS port + + + system shell + + + + SERIAL_CONTROL flags (bitmask) + + Set if this is a reply + + + Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message + + + Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set + + + Block on writes to the serial port + + + Send multiple replies until port is drained + + + + Enumeration of distance sensor types + + Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units + + + Ultrasound rangefinder, e.g. MaxBotix units + + + Infrared rangefinder, e.g. Sharp units + + + + Enumeration of sensor orientation, according to its rotations + + Roll: 0, Pitch: 0, Yaw: 0 + + + Roll: 0, Pitch: 0, Yaw: 45 + + + Roll: 0, Pitch: 0, Yaw: 90 + + + Roll: 0, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 0, Yaw: 180 + + + Roll: 0, Pitch: 0, Yaw: 225 + + + Roll: 0, Pitch: 0, Yaw: 270 + + + Roll: 0, Pitch: 0, Yaw: 315 + + + Roll: 180, Pitch: 0, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 45 + + + Roll: 180, Pitch: 0, Yaw: 90 + + + Roll: 180, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 180, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 225 + + + Roll: 180, Pitch: 0, Yaw: 270 + + + Roll: 180, Pitch: 0, Yaw: 315 + + + Roll: 90, Pitch: 0, Yaw: 0 + + + Roll: 90, Pitch: 0, Yaw: 45 + + + Roll: 90, Pitch: 0, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 135 + + + Roll: 270, Pitch: 0, Yaw: 0 + + + Roll: 270, Pitch: 0, Yaw: 45 + + + Roll: 270, Pitch: 0, Yaw: 90 + + + Roll: 270, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 90, Yaw: 0 + + + Roll: 0, Pitch: 270, Yaw: 0 + + + Roll: 0, Pitch: 180, Yaw: 90 + + + Roll: 0, Pitch: 180, Yaw: 270 + + + Roll: 90, Pitch: 90, Yaw: 0 + + + Roll: 180, Pitch: 90, Yaw: 0 + + + Roll: 270, Pitch: 90, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 0 + + + Roll: 270, Pitch: 180, Yaw: 0 + + + Roll: 90, Pitch: 270, Yaw: 0 + + + Roll: 180, Pitch: 270, Yaw: 0 + + + Roll: 270, Pitch: 270, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 270 + + + Roll: 315, Pitch: 315, Yaw: 315 + + + + Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. + + Autopilot supports MISSION float message type. + + + Autopilot supports the new param float message type. + + + Autopilot supports MISSION_INT scaled integer message type. + + + Autopilot supports COMMAND_INT scaled integer message type. + + + Autopilot supports the new param union message type. + + + Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. + + + Autopilot supports commanding attitude offboard. + + + Autopilot supports commanding position and velocity targets in local NED frame. + + + Autopilot supports commanding position and velocity targets in global scaled integers. + + + Autopilot supports terrain protocol / data handling. + + + Autopilot supports direct actuator control. + + + Autopilot supports the flight termination command. + + + Autopilot supports onboard compass calibration. + + + + Enumeration of estimator types + + This is a naive estimator without any real covariance feedback. + + + Computer vision based estimate. Might be up to scale. + + + Visual-inertial estimate. + + + Plain GPS estimate. + + + Estimator integrating GPS and inertial sensing. + + + + Enumeration of battery types + + Not specified. + + + Lithium polymer battery + + + Lithium-iron-phosphate battery + + + Lithium-ION battery + + + Nickel metal hydride battery + + + + Enumeration of battery functions + + Battery function is unknown + + + Battery supports all flight systems + + + Battery for the propulsion system + + + Avionics battery + + + Payload battery + + + + Enumeration of VTOL states + + MAV is not configured as VTOL + + + VTOL is in transition from multicopter to fixed-wing + + + VTOL is in transition from fixed-wing to multicopter + + + VTOL is in multicopter state + + + VTOL is in fixed-wing state + + + + Enumeration of landed detector states + + MAV landed state is unknown + + + MAV is landed (on ground) + + + MAV is in air + + + + Enumeration of the ADSB altimeter types + + Altitude reported from a Baro source using QNH reference + + + Altitude reported from a GNSS source + + + + ADSB classification for the type of vehicle emitting the transponder signal + + + + + + + + + + + + + + + + + + + + + + + These flags indicate status such as data validity of each data source. Set = data valid + + + + + + + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + Timestamp of the component clock since boot time in milliseconds. + + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new base mode + The new autopilot-specific mode. This field can be ignored by an autopilot. + + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw, 0 if nonexistant) + Differential pressure 2 (raw, 0 if nonexistant) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (milliseconds since system boot) + Roll angle (rad, -pi..+pi) + Pitch angle (rad, -pi..+pi) + Yaw angle (rad, -pi..+pi) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion component 1, w (1 in null-rotation) + Quaternion component 2, x (0 in null-rotation) + Quaternion component 3, y (0 in null-rotation) + Quaternion component 4, z (0 in null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the resolution of float is not sufficient. + Timestamp (milliseconds since system boot) + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude, positive north), expressed as m/s * 100 + Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Timestamp (microseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint. + System ID + Component ID + Start index, 0 by default + End index, -1 by default (-1: send list to end). Else a valid index of the list + + + This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! + System ID + Component ID + Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + End index, equal or greater than start index. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Sequence + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + + + Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol + System ID + Component ID + Sequence + + + Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs. + System ID + Component ID + Number of mission items in the sequence + + + Delete all mission items at once. + System ID + Component ID + + + A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. + Sequence + + + Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + See MAV_MISSION_RESULT enum + + + As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + Initial parameter value + Scale, maps the RC range [-1, 1] to a parameter value + Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Attitude covariance + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters. + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current MISSION/target in degrees + Distance to active MISSION in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. + Timestamp (milliseconds since system boot) + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), above MSL + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s + Ground Y Speed (Longitude), expressed as m/s + Ground Z Speed (Altitude), expressed as m/s + Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + X Position + Y Position + Z Position + X Speed (m/s) + Y Speed (m/s) + Z Speed (m/s) + X Acceleration (m/s^2) + Y Acceleration (m/s^2) + Z Acceleration (m/s^2) + Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + + + The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested data stream + The requested message rate + 1 to start sending, 0 to stop sending. + + + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + The ID of the requested data stream + The message rate + 1 stream is enabled, 0 stream is stopped. + + + This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their + The system to be controlled. + X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. + System ID + Component ID + The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Send a command with up to seven parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + Parameter 5, as defined by MAV_CMD enum. + Parameter 6, as defined by MAV_CMD enum. + Parameter 7, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed. + Command ID, as defined by MAV_CMD enum. + See MAV_RESULT enum + + + Setpoint in roll, pitch, yaw and thrust from the operator + Timestamp in milliseconds since system boot + Desired roll rate in radians per second + Desired pitch rate in radians per second + Desired yaw rate in radians per second + Collective thrust, normalized to 0 .. 1 + Flight mode switch position, 0.. 255 + Override mode switch position, 0.. 255 + + + Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + System ID + Component ID + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + Roll + Pitch + Yaw + + + DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Sent from autopilot to simulation. Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -1 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + Aux 1, -1 .. 1 + Aux 2, -1 .. 1 + Aux 3, -1 .. 1 + Aux 4, -1 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + RC channel 9 value, in microseconds + RC channel 10 value, in microseconds + RC channel 11 value, in microseconds + RC channel 12 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels * 10 in x-sensor direction (dezi-pixels) + Flow in pixels * 10 in y-sensor direction (dezi-pixels) + Flow in meters in x-sensor direction, angular-speed compensated + Flow in meters in y-sensor direction, angular-speed compensated + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X speed + Global Y speed + Global Z speed + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis (rad / sec) + Angular speed around Y axis (rad / sec) + Angular speed around Z axis (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + + + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis in body frame (rad / sec) + Angular speed around Y axis in body frame (rad / sec) + Angular speed around Z axis in body frame (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure (airspeed) in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + + + + Status of simulation environment, if used + True attitude quaternion component 1, w (1 in null-rotation) + True attitude quaternion component 2, x (0 in null-rotation) + True attitude quaternion component 3, y (0 in null-rotation) + True attitude quaternion component 4, z (0 in null-rotation) + Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees + Longitude in degrees + Altitude in meters + Horizontal position standard deviation + Vertical position standard deviation + True velocity in m/s in NORTH direction in earth-fixed NED frame + True velocity in m/s in EAST direction in earth-fixed NED frame + True velocity in m/s in DOWN direction in earth-fixed NED frame + + + + Status generated by radio and injected into MAVLink stream. + Local signal strength + Remote signal strength + Remaining free buffer space in percent. + Background noise level + Remote background noise level + Receive errors + Count of error corrected packets + + + File transfer message + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Time synchronization message. + Time sync timestamp 1 + Time sync timestamp 2 + + + Camera-IMU triggering and synchronisation message. + Timestamp for the image frame in microseconds + Image frame sequence + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + GPS ground speed (m/s * 100). If unknown, set to: 65535 + GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + GPS velocity in cm/s in EAST direction in earth-fixed NED frame + GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Number of satellites visible. If unknown, set to 255 + + + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + Indicated airspeed, expressed as m/s * 100 + True airspeed, expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. + System ID + Component ID + First log id (0 for first available) + Last log id (0xffff for last available) + + + Reply to LOG_REQUEST_LIST + Log id + Total number of logs + High log number + UTC timestamp of log in seconds since 1970, or 0 if not available + Size of the log (may be approximate) in bytes + + + Request a chunk of a log + System ID + Component ID + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes + + + Reply to LOG_REQUEST_DATA + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes (zero for end of log) + log data + + + Erase all logs + System ID + Component ID + + + Stop log transfer and resume normal logging + System ID + Component ID + + + data for injecting into the onboard GPS (used for DGPS) + System ID + Component ID + data length + raw data (110 is enough for 12 satellites of RTCMv2) + + + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + Number of DGPS satellites + Age of DGPS info + + + Power supply status + 5V rail voltage in millivolts + servo rail voltage in millivolts + power supply status flags (see MAV_POWER_STATUS enum) + + + Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. + See SERIAL_CONTROL_DEV enum + See SERIAL_CONTROL_FLAG enum + Timeout for reply data in milliseconds + Baudrate of transfer. Zero means no change. + how many bytes in this transfer + serial data + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + Width of a matrix or image + Height of a matrix or image + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + sequence number (starting with 0 on every transmission) + image data bytes + + + Time since system boot + Minimum distance the sensor can measure in centimeters + Maximum distance the sensor can measure in centimeters + Current distance reading + Type from MAV_DISTANCE_SENSOR enum. + Onboard ID of the sensor + Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + Measurement covariance in centimeters, 0 for unknown / invalid readings + + + Request for terrain data and terrain status + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + + + Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + bit within the terrain request mask + Terrain data in meters AMSL + + + Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. + Latitude (degrees *10^7) + Longitude (degrees *10^7) + + + Response from a TERRAIN_CHECK request + Latitude (degrees *10^7) + Longitude (degrees *10^7) + grid spacing (zero if terrain at this location unavailable) + Terrain height in meters AMSL + Current vehicle height above lat/lon terrain height (meters) + Number of 4x4 terrain blocks waiting to be received or read from disk + Number of 4x4 terrain blocks in memory + + + Barometer readings for 2nd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + Motion capture attitude and position + Timestamp (micros since boot or Unix epoch) + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + X position in meters (NED) + Y position in meters (NED) + Z position in meters (NED) + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + System ID + Component ID + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + The current system altitude. + Timestamp (milliseconds since system boot) + This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + This is the altitude above the home position. It resets on each change of the current home position. + This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + + + The autopilot is requesting a resource (file, binary, other type of data) + Request ID. This ID should be re-used when sending back URI contents + The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + + + Barometer readings for 3rd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + current motion information from a designated system + Timestamp in milliseconds since system boot + bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + AMSL, in meters + target velocity (0,0,0) for unknown + linear target acceleration (0,0,0) for unknown + (1 0 0 0 for unknown) + (0 0 0 for unknown) + eph epv + button states or switches of a tracker device + + + The smoothed, monotonic system state used to feed the control loops of the system. + Timestamp (micros since boot or Unix epoch) + X acceleration in body frame + Y acceleration in body frame + Z acceleration in body frame + X velocity in body frame + Y velocity in body frame + Z velocity in body frame + X position in local frame + Y position in local frame + Z position in local frame + Airspeed, set to -1 if unknown + Variance of body velocity estimate + Variance in local position + The attitude, represented as Quaternion + Angular rate in roll axis + Angular rate in pitch axis + Angular rate in yaw axis + + + Battery information + Battery ID + Function of the battery + Type (chemistry) of the battery + Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + + + Version and capability of autopilot software + bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + Firmware version number + Middleware version number + Operating system version number + HW / board version (last 8 bytes should be silicon ID, if any) + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + ID of the board vendor + ID of the product + UID if provided by hardware + + + The location of a landing area captured from a downward facing camera + Timestamp (micros since boot or Unix epoch) + The ID of the target if multiple targets are present + MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + X-axis angular offset (in radians) of the target from the center of the image + Y-axis angular offset (in radians) of the target from the center of the image + Distance to the target from the vehicle in meters + Size in radians of target along x-axis + Size in radians of target along y-axis + + + + Vibration levels and accelerometer clipping + Timestamp (micros since boot or Unix epoch) + Vibration levels on X-axis + Vibration levels on Y-axis + Vibration levels on Z-axis + first accelerometer clipping count + second accelerometer clipping count + third accelerometer clipping count + + + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + System ID. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + This interface replaces DATA_STREAM + The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + + + Provides state for additional features + The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + + + The location and information of an ADSB vehicle + ICAO address + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Type from ADSB_ALTITUDE_TYPE enum + Altitude(ASL) in millimeters + Course over ground in centidegrees + The horizontal velocity in centimeters/second + The vertical velocity in centimeters/second, positive is up + The callsign, 8+null + Type from ADSB_EMITTER_TYPE enum + Time since last communication in seconds + Flags to indicate various statuses including valid data fields + Squawk code + + + Message implementing parts of the V2 payload specs in V1 frames for transitional support. + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Starting address of the debug variables + Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + Memory contents at specified address + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + Timestamp (milliseconds since system boot) + index of debug variable + DEBUG value + + + diff --git a/pymavlink/dialects/v10/matrixpilot.py b/pymavlink/dialects/v10/matrixpilot.py new file mode 100644 index 0000000..76f4fbc --- /dev/null +++ b/pymavlink/dialects/v10/matrixpilot.py @@ -0,0 +1,12307 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: matrixpilot.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "matrixpilot" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_AUTOPILOT +enums['MAV_AUTOPILOT'] = {} +MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything +enums['MAV_AUTOPILOT'][0] = EnumEntry('MAV_AUTOPILOT_GENERIC', '''Generic autopilot, full support for everything''') +MAV_AUTOPILOT_RESERVED = 1 # Reserved for future use. +enums['MAV_AUTOPILOT'][1] = EnumEntry('MAV_AUTOPILOT_RESERVED', '''Reserved for future use.''') +MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu +enums['MAV_AUTOPILOT'][2] = EnumEntry('MAV_AUTOPILOT_SLUGS', '''SLUGS autopilot, http://slugsuav.soe.ucsc.edu''') +MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com +enums['MAV_AUTOPILOT'][3] = EnumEntry('MAV_AUTOPILOT_ARDUPILOTMEGA', '''ArduPilotMega / ArduCopter, http://diydrones.com''') +MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org +enums['MAV_AUTOPILOT'][4] = EnumEntry('MAV_AUTOPILOT_OPENPILOT', '''OpenPilot, http://openpilot.org''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints +enums['MAV_AUTOPILOT'][5] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY', '''Generic autopilot only supporting simple waypoints''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation + # commands +enums['MAV_AUTOPILOT'][6] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY', '''Generic autopilot supporting waypoints and other simple navigation commands''') +MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set +enums['MAV_AUTOPILOT'][7] = EnumEntry('MAV_AUTOPILOT_GENERIC_MISSION_FULL', '''Generic autopilot supporting the full mission command set''') +MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component +enums['MAV_AUTOPILOT'][8] = EnumEntry('MAV_AUTOPILOT_INVALID', '''No valid autopilot, e.g. a GCS or other MAVLink component''') +MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi +enums['MAV_AUTOPILOT'][9] = EnumEntry('MAV_AUTOPILOT_PPZ', '''PPZ UAV - http://nongnu.org/paparazzi''') +MAV_AUTOPILOT_UDB = 10 # UAV Dev Board +enums['MAV_AUTOPILOT'][10] = EnumEntry('MAV_AUTOPILOT_UDB', '''UAV Dev Board''') +MAV_AUTOPILOT_FP = 11 # FlexiPilot +enums['MAV_AUTOPILOT'][11] = EnumEntry('MAV_AUTOPILOT_FP', '''FlexiPilot''') +MAV_AUTOPILOT_PX4 = 12 # PX4 Autopilot - http://pixhawk.ethz.ch/px4/ +enums['MAV_AUTOPILOT'][12] = EnumEntry('MAV_AUTOPILOT_PX4', '''PX4 Autopilot - http://pixhawk.ethz.ch/px4/''') +MAV_AUTOPILOT_SMACCMPILOT = 13 # SMACCMPilot - http://smaccmpilot.org +enums['MAV_AUTOPILOT'][13] = EnumEntry('MAV_AUTOPILOT_SMACCMPILOT', '''SMACCMPilot - http://smaccmpilot.org''') +MAV_AUTOPILOT_AUTOQUAD = 14 # AutoQuad -- http://autoquad.org +enums['MAV_AUTOPILOT'][14] = EnumEntry('MAV_AUTOPILOT_AUTOQUAD', '''AutoQuad -- http://autoquad.org''') +MAV_AUTOPILOT_ARMAZILA = 15 # Armazila -- http://armazila.com +enums['MAV_AUTOPILOT'][15] = EnumEntry('MAV_AUTOPILOT_ARMAZILA', '''Armazila -- http://armazila.com''') +MAV_AUTOPILOT_AEROB = 16 # Aerob -- http://aerob.ru +enums['MAV_AUTOPILOT'][16] = EnumEntry('MAV_AUTOPILOT_AEROB', '''Aerob -- http://aerob.ru''') +MAV_AUTOPILOT_ASLUAV = 17 # ASLUAV autopilot -- http://www.asl.ethz.ch +enums['MAV_AUTOPILOT'][17] = EnumEntry('MAV_AUTOPILOT_ASLUAV', '''ASLUAV autopilot -- http://www.asl.ethz.ch''') +MAV_AUTOPILOT_ENUM_END = 18 # +enums['MAV_AUTOPILOT'][18] = EnumEntry('MAV_AUTOPILOT_ENUM_END', '''''') + +# MAV_TYPE +enums['MAV_TYPE'] = {} +MAV_TYPE_GENERIC = 0 # Generic micro air vehicle. +enums['MAV_TYPE'][0] = EnumEntry('MAV_TYPE_GENERIC', '''Generic micro air vehicle.''') +MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft. +enums['MAV_TYPE'][1] = EnumEntry('MAV_TYPE_FIXED_WING', '''Fixed wing aircraft.''') +MAV_TYPE_QUADROTOR = 2 # Quadrotor +enums['MAV_TYPE'][2] = EnumEntry('MAV_TYPE_QUADROTOR', '''Quadrotor''') +MAV_TYPE_COAXIAL = 3 # Coaxial helicopter +enums['MAV_TYPE'][3] = EnumEntry('MAV_TYPE_COAXIAL', '''Coaxial helicopter''') +MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor. +enums['MAV_TYPE'][4] = EnumEntry('MAV_TYPE_HELICOPTER', '''Normal helicopter with tail rotor.''') +MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation +enums['MAV_TYPE'][5] = EnumEntry('MAV_TYPE_ANTENNA_TRACKER', '''Ground installation''') +MAV_TYPE_GCS = 6 # Operator control unit / ground control station +enums['MAV_TYPE'][6] = EnumEntry('MAV_TYPE_GCS', '''Operator control unit / ground control station''') +MAV_TYPE_AIRSHIP = 7 # Airship, controlled +enums['MAV_TYPE'][7] = EnumEntry('MAV_TYPE_AIRSHIP', '''Airship, controlled''') +MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled +enums['MAV_TYPE'][8] = EnumEntry('MAV_TYPE_FREE_BALLOON', '''Free balloon, uncontrolled''') +MAV_TYPE_ROCKET = 9 # Rocket +enums['MAV_TYPE'][9] = EnumEntry('MAV_TYPE_ROCKET', '''Rocket''') +MAV_TYPE_GROUND_ROVER = 10 # Ground rover +enums['MAV_TYPE'][10] = EnumEntry('MAV_TYPE_GROUND_ROVER', '''Ground rover''') +MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship +enums['MAV_TYPE'][11] = EnumEntry('MAV_TYPE_SURFACE_BOAT', '''Surface vessel, boat, ship''') +MAV_TYPE_SUBMARINE = 12 # Submarine +enums['MAV_TYPE'][12] = EnumEntry('MAV_TYPE_SUBMARINE', '''Submarine''') +MAV_TYPE_HEXAROTOR = 13 # Hexarotor +enums['MAV_TYPE'][13] = EnumEntry('MAV_TYPE_HEXAROTOR', '''Hexarotor''') +MAV_TYPE_OCTOROTOR = 14 # Octorotor +enums['MAV_TYPE'][14] = EnumEntry('MAV_TYPE_OCTOROTOR', '''Octorotor''') +MAV_TYPE_TRICOPTER = 15 # Octorotor +enums['MAV_TYPE'][15] = EnumEntry('MAV_TYPE_TRICOPTER', '''Octorotor''') +MAV_TYPE_FLAPPING_WING = 16 # Flapping wing +enums['MAV_TYPE'][16] = EnumEntry('MAV_TYPE_FLAPPING_WING', '''Flapping wing''') +MAV_TYPE_KITE = 17 # Flapping wing +enums['MAV_TYPE'][17] = EnumEntry('MAV_TYPE_KITE', '''Flapping wing''') +MAV_TYPE_ONBOARD_CONTROLLER = 18 # Onboard companion controller +enums['MAV_TYPE'][18] = EnumEntry('MAV_TYPE_ONBOARD_CONTROLLER', '''Onboard companion controller''') +MAV_TYPE_VTOL_DUOROTOR = 19 # Two-rotor VTOL using control surfaces in vertical operation in + # addition. Tailsitter. +enums['MAV_TYPE'][19] = EnumEntry('MAV_TYPE_VTOL_DUOROTOR', '''Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.''') +MAV_TYPE_VTOL_QUADROTOR = 20 # Quad-rotor VTOL using a V-shaped quad config in vertical operation. + # Tailsitter. +enums['MAV_TYPE'][20] = EnumEntry('MAV_TYPE_VTOL_QUADROTOR', '''Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.''') +MAV_TYPE_VTOL_TILTROTOR = 21 # Tiltrotor VTOL +enums['MAV_TYPE'][21] = EnumEntry('MAV_TYPE_VTOL_TILTROTOR', '''Tiltrotor VTOL''') +MAV_TYPE_VTOL_RESERVED2 = 22 # VTOL reserved 2 +enums['MAV_TYPE'][22] = EnumEntry('MAV_TYPE_VTOL_RESERVED2', '''VTOL reserved 2''') +MAV_TYPE_VTOL_RESERVED3 = 23 # VTOL reserved 3 +enums['MAV_TYPE'][23] = EnumEntry('MAV_TYPE_VTOL_RESERVED3', '''VTOL reserved 3''') +MAV_TYPE_VTOL_RESERVED4 = 24 # VTOL reserved 4 +enums['MAV_TYPE'][24] = EnumEntry('MAV_TYPE_VTOL_RESERVED4', '''VTOL reserved 4''') +MAV_TYPE_VTOL_RESERVED5 = 25 # VTOL reserved 5 +enums['MAV_TYPE'][25] = EnumEntry('MAV_TYPE_VTOL_RESERVED5', '''VTOL reserved 5''') +MAV_TYPE_GIMBAL = 26 # Onboard gimbal +enums['MAV_TYPE'][26] = EnumEntry('MAV_TYPE_GIMBAL', '''Onboard gimbal''') +MAV_TYPE_ADSB = 27 # Onboard ADSB peripheral +enums['MAV_TYPE'][27] = EnumEntry('MAV_TYPE_ADSB', '''Onboard ADSB peripheral''') +MAV_TYPE_ENUM_END = 28 # +enums['MAV_TYPE'][28] = EnumEntry('MAV_TYPE_ENUM_END', '''''') + +# FIRMWARE_VERSION_TYPE +enums['FIRMWARE_VERSION_TYPE'] = {} +FIRMWARE_VERSION_TYPE_DEV = 0 # development release +enums['FIRMWARE_VERSION_TYPE'][0] = EnumEntry('FIRMWARE_VERSION_TYPE_DEV', '''development release''') +FIRMWARE_VERSION_TYPE_ALPHA = 64 # alpha release +enums['FIRMWARE_VERSION_TYPE'][64] = EnumEntry('FIRMWARE_VERSION_TYPE_ALPHA', '''alpha release''') +FIRMWARE_VERSION_TYPE_BETA = 128 # beta release +enums['FIRMWARE_VERSION_TYPE'][128] = EnumEntry('FIRMWARE_VERSION_TYPE_BETA', '''beta release''') +FIRMWARE_VERSION_TYPE_RC = 192 # release candidate +enums['FIRMWARE_VERSION_TYPE'][192] = EnumEntry('FIRMWARE_VERSION_TYPE_RC', '''release candidate''') +FIRMWARE_VERSION_TYPE_OFFICIAL = 255 # official stable release +enums['FIRMWARE_VERSION_TYPE'][255] = EnumEntry('FIRMWARE_VERSION_TYPE_OFFICIAL', '''official stable release''') +FIRMWARE_VERSION_TYPE_ENUM_END = 256 # +enums['FIRMWARE_VERSION_TYPE'][256] = EnumEntry('FIRMWARE_VERSION_TYPE_ENUM_END', '''''') + +# MAV_MODE_FLAG +enums['MAV_MODE_FLAG'] = {} +MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use. +enums['MAV_MODE_FLAG'][1] = EnumEntry('MAV_MODE_FLAG_CUSTOM_MODE_ENABLED', '''0b00000001 Reserved for future use.''') +MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for + # temporary system tests and should not be + # used for stable implementations. +enums['MAV_MODE_FLAG'][2] = EnumEntry('MAV_MODE_FLAG_TEST_ENABLED', '''0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.''') +MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal + # positions. Guided flag can be set or not, + # depends on the actual implementation. +enums['MAV_MODE_FLAG'][4] = EnumEntry('MAV_MODE_FLAG_AUTO_ENABLED', '''0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.''') +MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items. +enums['MAV_MODE_FLAG'][8] = EnumEntry('MAV_MODE_FLAG_GUIDED_ENABLED', '''0b00001000 guided mode enabled, system flies MISSIONs / mission items.''') +MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and + # optionally position). It needs however + # further control inputs to move around. +enums['MAV_MODE_FLAG'][16] = EnumEntry('MAV_MODE_FLAG_STABILIZE_ENABLED', '''0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.''') +MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are + # blocked, but internal software is full + # operational. +enums['MAV_MODE_FLAG'][32] = EnumEntry('MAV_MODE_FLAG_HIL_ENABLED', '''0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.''') +MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled. +enums['MAV_MODE_FLAG'][64] = EnumEntry('MAV_MODE_FLAG_MANUAL_INPUT_ENABLED', '''0b01000000 remote control input is enabled.''') +MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can + # start. Ready to fly. +enums['MAV_MODE_FLAG'][128] = EnumEntry('MAV_MODE_FLAG_SAFETY_ARMED', '''0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.''') +MAV_MODE_FLAG_ENUM_END = 129 # +enums['MAV_MODE_FLAG'][129] = EnumEntry('MAV_MODE_FLAG_ENUM_END', '''''') + +# MAV_MODE_FLAG_DECODE_POSITION +enums['MAV_MODE_FLAG_DECODE_POSITION'] = {} +MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001 +enums['MAV_MODE_FLAG_DECODE_POSITION'][1] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE', '''Eighth bit: 00000001''') +MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010 +enums['MAV_MODE_FLAG_DECODE_POSITION'][2] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_TEST', '''Seventh bit: 00000010''') +MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100 +enums['MAV_MODE_FLAG_DECODE_POSITION'][4] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_AUTO', '''Sixt bit: 00000100''') +MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][8] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_GUIDED', '''Fifth bit: 00001000''') +MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][16] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_STABILIZE', '''Fourth bit: 00010000''') +MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][32] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_HIL', '''Third bit: 00100000''') +MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][64] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_MANUAL', '''Second bit: 01000000''') +MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][128] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_SAFETY', '''First bit: 10000000''') +MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 # +enums['MAV_MODE_FLAG_DECODE_POSITION'][129] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_ENUM_END', '''''') + +# MAV_GOTO +enums['MAV_GOTO'] = {} +MAV_GOTO_DO_HOLD = 0 # Hold at the current position. +enums['MAV_GOTO'][0] = EnumEntry('MAV_GOTO_DO_HOLD', '''Hold at the current position.''') +MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution. +enums['MAV_GOTO'][1] = EnumEntry('MAV_GOTO_DO_CONTINUE', '''Continue with the next item in mission execution.''') +MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system +enums['MAV_GOTO'][2] = EnumEntry('MAV_GOTO_HOLD_AT_CURRENT_POSITION', '''Hold at the current position of the system''') +MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action +enums['MAV_GOTO'][3] = EnumEntry('MAV_GOTO_HOLD_AT_SPECIFIED_POSITION', '''Hold at the position specified in the parameters of the DO_HOLD action''') +MAV_GOTO_ENUM_END = 4 # +enums['MAV_GOTO'][4] = EnumEntry('MAV_GOTO_ENUM_END', '''''') + +# MAV_MODE +enums['MAV_MODE'] = {} +MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set. +enums['MAV_MODE'][0] = EnumEntry('MAV_MODE_PREFLIGHT', '''System is not ready to fly, booting, calibrating, etc. No flag is set.''') +MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][64] = EnumEntry('MAV_MODE_MANUAL_DISARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][66] = EnumEntry('MAV_MODE_TEST_DISARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][80] = EnumEntry('MAV_MODE_STABILIZE_DISARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][88] = EnumEntry('MAV_MODE_GUIDED_DISARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][92] = EnumEntry('MAV_MODE_AUTO_DISARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][192] = EnumEntry('MAV_MODE_MANUAL_ARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][194] = EnumEntry('MAV_MODE_TEST_ARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][208] = EnumEntry('MAV_MODE_STABILIZE_ARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][216] = EnumEntry('MAV_MODE_GUIDED_ARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][220] = EnumEntry('MAV_MODE_AUTO_ARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_ENUM_END = 221 # +enums['MAV_MODE'][221] = EnumEntry('MAV_MODE_ENUM_END', '''''') + +# MAV_STATE +enums['MAV_STATE'] = {} +MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown. +enums['MAV_STATE'][0] = EnumEntry('MAV_STATE_UNINIT', '''Uninitialized system, state is unknown.''') +MAV_STATE_BOOT = 1 # System is booting up. +enums['MAV_STATE'][1] = EnumEntry('MAV_STATE_BOOT', '''System is booting up.''') +MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready. +enums['MAV_STATE'][2] = EnumEntry('MAV_STATE_CALIBRATING', '''System is calibrating and not flight-ready.''') +MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time. +enums['MAV_STATE'][3] = EnumEntry('MAV_STATE_STANDBY', '''System is grounded and on standby. It can be launched any time.''') +MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged. +enums['MAV_STATE'][4] = EnumEntry('MAV_STATE_ACTIVE', '''System is active and might be already airborne. Motors are engaged.''') +MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate. +enums['MAV_STATE'][5] = EnumEntry('MAV_STATE_CRITICAL', '''System is in a non-normal flight mode. It can however still navigate.''') +MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or + # over the whole airframe. It is in mayday and + # going down. +enums['MAV_STATE'][6] = EnumEntry('MAV_STATE_EMERGENCY', '''System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.''') +MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now. +enums['MAV_STATE'][7] = EnumEntry('MAV_STATE_POWEROFF', '''System just initialized its power-down sequence, will shut down now.''') +MAV_STATE_ENUM_END = 8 # +enums['MAV_STATE'][8] = EnumEntry('MAV_STATE_ENUM_END', '''''') + +# MAV_COMPONENT +enums['MAV_COMPONENT'] = {} +MAV_COMP_ID_ALL = 0 # +enums['MAV_COMPONENT'][0] = EnumEntry('MAV_COMP_ID_ALL', '''''') +MAV_COMP_ID_CAMERA = 100 # +enums['MAV_COMPONENT'][100] = EnumEntry('MAV_COMP_ID_CAMERA', '''''') +MAV_COMP_ID_SERVO1 = 140 # +enums['MAV_COMPONENT'][140] = EnumEntry('MAV_COMP_ID_SERVO1', '''''') +MAV_COMP_ID_SERVO2 = 141 # +enums['MAV_COMPONENT'][141] = EnumEntry('MAV_COMP_ID_SERVO2', '''''') +MAV_COMP_ID_SERVO3 = 142 # +enums['MAV_COMPONENT'][142] = EnumEntry('MAV_COMP_ID_SERVO3', '''''') +MAV_COMP_ID_SERVO4 = 143 # +enums['MAV_COMPONENT'][143] = EnumEntry('MAV_COMP_ID_SERVO4', '''''') +MAV_COMP_ID_SERVO5 = 144 # +enums['MAV_COMPONENT'][144] = EnumEntry('MAV_COMP_ID_SERVO5', '''''') +MAV_COMP_ID_SERVO6 = 145 # +enums['MAV_COMPONENT'][145] = EnumEntry('MAV_COMP_ID_SERVO6', '''''') +MAV_COMP_ID_SERVO7 = 146 # +enums['MAV_COMPONENT'][146] = EnumEntry('MAV_COMP_ID_SERVO7', '''''') +MAV_COMP_ID_SERVO8 = 147 # +enums['MAV_COMPONENT'][147] = EnumEntry('MAV_COMP_ID_SERVO8', '''''') +MAV_COMP_ID_SERVO9 = 148 # +enums['MAV_COMPONENT'][148] = EnumEntry('MAV_COMP_ID_SERVO9', '''''') +MAV_COMP_ID_SERVO10 = 149 # +enums['MAV_COMPONENT'][149] = EnumEntry('MAV_COMP_ID_SERVO10', '''''') +MAV_COMP_ID_SERVO11 = 150 # +enums['MAV_COMPONENT'][150] = EnumEntry('MAV_COMP_ID_SERVO11', '''''') +MAV_COMP_ID_SERVO12 = 151 # +enums['MAV_COMPONENT'][151] = EnumEntry('MAV_COMP_ID_SERVO12', '''''') +MAV_COMP_ID_SERVO13 = 152 # +enums['MAV_COMPONENT'][152] = EnumEntry('MAV_COMP_ID_SERVO13', '''''') +MAV_COMP_ID_SERVO14 = 153 # +enums['MAV_COMPONENT'][153] = EnumEntry('MAV_COMP_ID_SERVO14', '''''') +MAV_COMP_ID_GIMBAL = 154 # +enums['MAV_COMPONENT'][154] = EnumEntry('MAV_COMP_ID_GIMBAL', '''''') +MAV_COMP_ID_LOG = 155 # +enums['MAV_COMPONENT'][155] = EnumEntry('MAV_COMP_ID_LOG', '''''') +MAV_COMP_ID_ADSB = 156 # +enums['MAV_COMPONENT'][156] = EnumEntry('MAV_COMP_ID_ADSB', '''''') +MAV_COMP_ID_OSD = 157 # On Screen Display (OSD) devices for video links +enums['MAV_COMPONENT'][157] = EnumEntry('MAV_COMP_ID_OSD', '''On Screen Display (OSD) devices for video links''') +MAV_COMP_ID_PERIPHERAL = 158 # Generic autopilot peripheral component ID. Meant for devices that do + # not implement the parameter sub-protocol +enums['MAV_COMPONENT'][158] = EnumEntry('MAV_COMP_ID_PERIPHERAL', '''Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol''') +MAV_COMP_ID_MAPPER = 180 # +enums['MAV_COMPONENT'][180] = EnumEntry('MAV_COMP_ID_MAPPER', '''''') +MAV_COMP_ID_MISSIONPLANNER = 190 # +enums['MAV_COMPONENT'][190] = EnumEntry('MAV_COMP_ID_MISSIONPLANNER', '''''') +MAV_COMP_ID_PATHPLANNER = 195 # +enums['MAV_COMPONENT'][195] = EnumEntry('MAV_COMP_ID_PATHPLANNER', '''''') +MAV_COMP_ID_IMU = 200 # +enums['MAV_COMPONENT'][200] = EnumEntry('MAV_COMP_ID_IMU', '''''') +MAV_COMP_ID_IMU_2 = 201 # +enums['MAV_COMPONENT'][201] = EnumEntry('MAV_COMP_ID_IMU_2', '''''') +MAV_COMP_ID_IMU_3 = 202 # +enums['MAV_COMPONENT'][202] = EnumEntry('MAV_COMP_ID_IMU_3', '''''') +MAV_COMP_ID_GPS = 220 # +enums['MAV_COMPONENT'][220] = EnumEntry('MAV_COMP_ID_GPS', '''''') +MAV_COMP_ID_UDP_BRIDGE = 240 # +enums['MAV_COMPONENT'][240] = EnumEntry('MAV_COMP_ID_UDP_BRIDGE', '''''') +MAV_COMP_ID_UART_BRIDGE = 241 # +enums['MAV_COMPONENT'][241] = EnumEntry('MAV_COMP_ID_UART_BRIDGE', '''''') +MAV_COMP_ID_SYSTEM_CONTROL = 250 # +enums['MAV_COMPONENT'][250] = EnumEntry('MAV_COMP_ID_SYSTEM_CONTROL', '''''') +MAV_COMPONENT_ENUM_END = 251 # +enums['MAV_COMPONENT'][251] = EnumEntry('MAV_COMPONENT_ENUM_END', '''''') + +# MAV_SYS_STATUS_SENSOR +enums['MAV_SYS_STATUS_SENSOR'] = {} +MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 # 0x01 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][1] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO', '''0x01 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 # 0x02 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][2] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL', '''0x02 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG = 4 # 0x04 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][4] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG', '''0x04 3D magnetometer''') +MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 # 0x08 absolute pressure +enums['MAV_SYS_STATUS_SENSOR'][8] = EnumEntry('MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE', '''0x08 absolute pressure''') +MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 # 0x10 differential pressure +enums['MAV_SYS_STATUS_SENSOR'][16] = EnumEntry('MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE', '''0x10 differential pressure''') +MAV_SYS_STATUS_SENSOR_GPS = 32 # 0x20 GPS +enums['MAV_SYS_STATUS_SENSOR'][32] = EnumEntry('MAV_SYS_STATUS_SENSOR_GPS', '''0x20 GPS''') +MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 # 0x40 optical flow +enums['MAV_SYS_STATUS_SENSOR'][64] = EnumEntry('MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW', '''0x40 optical flow''') +MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 # 0x80 computer vision position +enums['MAV_SYS_STATUS_SENSOR'][128] = EnumEntry('MAV_SYS_STATUS_SENSOR_VISION_POSITION', '''0x80 computer vision position''') +MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 # 0x100 laser based position +enums['MAV_SYS_STATUS_SENSOR'][256] = EnumEntry('MAV_SYS_STATUS_SENSOR_LASER_POSITION', '''0x100 laser based position''') +MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 # 0x200 external ground truth (Vicon or Leica) +enums['MAV_SYS_STATUS_SENSOR'][512] = EnumEntry('MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH', '''0x200 external ground truth (Vicon or Leica)''') +MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 # 0x400 3D angular rate control +enums['MAV_SYS_STATUS_SENSOR'][1024] = EnumEntry('MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL', '''0x400 3D angular rate control''') +MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 # 0x800 attitude stabilization +enums['MAV_SYS_STATUS_SENSOR'][2048] = EnumEntry('MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION', '''0x800 attitude stabilization''') +MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 # 0x1000 yaw position +enums['MAV_SYS_STATUS_SENSOR'][4096] = EnumEntry('MAV_SYS_STATUS_SENSOR_YAW_POSITION', '''0x1000 yaw position''') +MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 # 0x2000 z/altitude control +enums['MAV_SYS_STATUS_SENSOR'][8192] = EnumEntry('MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL', '''0x2000 z/altitude control''') +MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 # 0x4000 x/y position control +enums['MAV_SYS_STATUS_SENSOR'][16384] = EnumEntry('MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL', '''0x4000 x/y position control''') +MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 # 0x8000 motor outputs / control +enums['MAV_SYS_STATUS_SENSOR'][32768] = EnumEntry('MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS', '''0x8000 motor outputs / control''') +MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 # 0x10000 rc receiver +enums['MAV_SYS_STATUS_SENSOR'][65536] = EnumEntry('MAV_SYS_STATUS_SENSOR_RC_RECEIVER', '''0x10000 rc receiver''') +MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 # 0x20000 2nd 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][131072] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO2', '''0x20000 2nd 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 # 0x40000 2nd 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][262144] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL2', '''0x40000 2nd 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 # 0x80000 2nd 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][524288] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG2', '''0x80000 2nd 3D magnetometer''') +MAV_SYS_STATUS_GEOFENCE = 1048576 # 0x100000 geofence +enums['MAV_SYS_STATUS_SENSOR'][1048576] = EnumEntry('MAV_SYS_STATUS_GEOFENCE', '''0x100000 geofence''') +MAV_SYS_STATUS_AHRS = 2097152 # 0x200000 AHRS subsystem health +enums['MAV_SYS_STATUS_SENSOR'][2097152] = EnumEntry('MAV_SYS_STATUS_AHRS', '''0x200000 AHRS subsystem health''') +MAV_SYS_STATUS_TERRAIN = 4194304 # 0x400000 Terrain subsystem health +enums['MAV_SYS_STATUS_SENSOR'][4194304] = EnumEntry('MAV_SYS_STATUS_TERRAIN', '''0x400000 Terrain subsystem health''') +MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 # 0x800000 Motors are reversed +enums['MAV_SYS_STATUS_SENSOR'][8388608] = EnumEntry('MAV_SYS_STATUS_REVERSE_MOTOR', '''0x800000 Motors are reversed''') +MAV_SYS_STATUS_SENSOR_ENUM_END = 8388609 # +enums['MAV_SYS_STATUS_SENSOR'][8388609] = EnumEntry('MAV_SYS_STATUS_SENSOR_ENUM_END', '''''') + +# MAV_FRAME +enums['MAV_FRAME'] = {} +MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude, second value / y: longitude, third + # value / z: positive altitude over mean sea + # level (MSL) +enums['MAV_FRAME'][0] = EnumEntry('MAV_FRAME_GLOBAL', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down). +enums['MAV_FRAME'][1] = EnumEntry('MAV_FRAME_LOCAL_NED', '''Local coordinate frame, Z-up (x: north, y: east, z: down).''') +MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command. +enums['MAV_FRAME'][2] = EnumEntry('MAV_FRAME_MISSION', '''NOT a coordinate frame, indicates a mission command.''') +MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude, second + # value / y: longitude, third value / z: + # positive altitude with 0 being at the + # altitude of the home location. +enums['MAV_FRAME'][3] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up) +enums['MAV_FRAME'][4] = EnumEntry('MAV_FRAME_LOCAL_ENU', '''Local coordinate frame, Z-down (x: east, y: north, z: up)''') +MAV_FRAME_GLOBAL_INT = 5 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude in degrees*1.0e-7, second value / + # y: longitude in degrees*1.0e-7, third value + # / z: positive altitude over mean sea level + # (MSL) +enums['MAV_FRAME'][5] = EnumEntry('MAV_FRAME_GLOBAL_INT', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude with 0 being at the altitude of the + # home location. +enums['MAV_FRAME'][6] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT_INT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame + # should be added to the current local frame + # position. +enums['MAV_FRAME'][7] = EnumEntry('MAV_FRAME_LOCAL_OFFSET_NED', '''Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.''') +MAV_FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control + # is externalized - e.g. useful to command 2 + # m/s^2 acceleration to the right. +enums['MAV_FRAME'][8] = EnumEntry('MAV_FRAME_BODY_NED', '''Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.''') +MAV_FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the + # current flight path, to avoid an obstacle - + # e.g. useful to command 2 m/s^2 acceleration + # to the east. +enums['MAV_FRAME'][9] = EnumEntry('MAV_FRAME_BODY_OFFSET_NED', '''Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees, second value / y: longitude in + # degrees, third value / z: positive altitude + # in meters with 0 being at ground level in + # terrain model. +enums['MAV_FRAME'][10] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude in meters with 0 being at ground + # level in terrain model. +enums['MAV_FRAME'][11] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT_INT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_ENUM_END = 12 # +enums['MAV_FRAME'][12] = EnumEntry('MAV_FRAME_ENUM_END', '''''') + +# MAVLINK_DATA_STREAM_TYPE +enums['MAVLINK_DATA_STREAM_TYPE'] = {} +MAVLINK_DATA_STREAM_IMG_JPEG = 1 # +enums['MAVLINK_DATA_STREAM_TYPE'][1] = EnumEntry('MAVLINK_DATA_STREAM_IMG_JPEG', '''''') +MAVLINK_DATA_STREAM_IMG_BMP = 2 # +enums['MAVLINK_DATA_STREAM_TYPE'][2] = EnumEntry('MAVLINK_DATA_STREAM_IMG_BMP', '''''') +MAVLINK_DATA_STREAM_IMG_RAW8U = 3 # +enums['MAVLINK_DATA_STREAM_TYPE'][3] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW8U', '''''') +MAVLINK_DATA_STREAM_IMG_RAW32U = 4 # +enums['MAVLINK_DATA_STREAM_TYPE'][4] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW32U', '''''') +MAVLINK_DATA_STREAM_IMG_PGM = 5 # +enums['MAVLINK_DATA_STREAM_TYPE'][5] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PGM', '''''') +MAVLINK_DATA_STREAM_IMG_PNG = 6 # +enums['MAVLINK_DATA_STREAM_TYPE'][6] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PNG', '''''') +MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 # +enums['MAVLINK_DATA_STREAM_TYPE'][7] = EnumEntry('MAVLINK_DATA_STREAM_TYPE_ENUM_END', '''''') + +# FENCE_ACTION +enums['FENCE_ACTION'] = {} +FENCE_ACTION_NONE = 0 # Disable fenced mode +enums['FENCE_ACTION'][0] = EnumEntry('FENCE_ACTION_NONE', '''Disable fenced mode''') +FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0) +enums['FENCE_ACTION'][1] = EnumEntry('FENCE_ACTION_GUIDED', '''Switched to guided mode to return point (fence point 0)''') +FENCE_ACTION_REPORT = 2 # Report fence breach, but don't take action +enums['FENCE_ACTION'][2] = EnumEntry('FENCE_ACTION_REPORT', '''Report fence breach, but don't take action''') +FENCE_ACTION_GUIDED_THR_PASS = 3 # Switched to guided mode to return point (fence point 0) with manual + # throttle control +enums['FENCE_ACTION'][3] = EnumEntry('FENCE_ACTION_GUIDED_THR_PASS', '''Switched to guided mode to return point (fence point 0) with manual throttle control''') +FENCE_ACTION_ENUM_END = 4 # +enums['FENCE_ACTION'][4] = EnumEntry('FENCE_ACTION_ENUM_END', '''''') + +# FENCE_BREACH +enums['FENCE_BREACH'] = {} +FENCE_BREACH_NONE = 0 # No last fence breach +enums['FENCE_BREACH'][0] = EnumEntry('FENCE_BREACH_NONE', '''No last fence breach''') +FENCE_BREACH_MINALT = 1 # Breached minimum altitude +enums['FENCE_BREACH'][1] = EnumEntry('FENCE_BREACH_MINALT', '''Breached minimum altitude''') +FENCE_BREACH_MAXALT = 2 # Breached maximum altitude +enums['FENCE_BREACH'][2] = EnumEntry('FENCE_BREACH_MAXALT', '''Breached maximum altitude''') +FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary +enums['FENCE_BREACH'][3] = EnumEntry('FENCE_BREACH_BOUNDARY', '''Breached fence boundary''') +FENCE_BREACH_ENUM_END = 4 # +enums['FENCE_BREACH'][4] = EnumEntry('FENCE_BREACH_ENUM_END', '''''') + +# MAV_MOUNT_MODE +enums['MAV_MOUNT_MODE'] = {} +MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permant memory and + # stop stabilization +enums['MAV_MOUNT_MODE'][0] = EnumEntry('MAV_MOUNT_MODE_RETRACT', '''Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization''') +MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +enums['MAV_MOUNT_MODE'][1] = EnumEntry('MAV_MOUNT_MODE_NEUTRAL', '''Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.''') +MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][2] = EnumEntry('MAV_MOUNT_MODE_MAVLINK_TARGETING', '''Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][3] = EnumEntry('MAV_MOUNT_MODE_RC_TARGETING', '''Load neutral position and start RC Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt +enums['MAV_MOUNT_MODE'][4] = EnumEntry('MAV_MOUNT_MODE_GPS_POINT', '''Load neutral position and start to point to Lat,Lon,Alt''') +MAV_MOUNT_MODE_ENUM_END = 5 # +enums['MAV_MOUNT_MODE'][5] = EnumEntry('MAV_MOUNT_MODE_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_FLEXIFUNCTION_SET = 150 +MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ = 151 +MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION = 152 +MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK = 153 +MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY = 155 +MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK = 156 +MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND = 157 +MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK = 158 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A = 170 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B = 171 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4 = 172 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5 = 173 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6 = 174 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7 = 175 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8 = 176 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13 = 177 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14 = 178 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15 = 179 +MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16 = 180 +MAVLINK_MSG_ID_ALTITUDES = 181 +MAVLINK_MSG_ID_AIRSPEEDS = 182 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_flexifunction_set_message(MAVLink_message): + ''' + Depreciated but used as a compiler flag. Do not remove + ''' + id = MAVLINK_MSG_ID_FLEXIFUNCTION_SET + name = 'FLEXIFUNCTION_SET' + fieldnames = ['target_system', 'target_component'] + ordered_fieldnames = [ 'target_system', 'target_component' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/matrixpilot.xml b/pymavlink/dialects/v10/matrixpilot.xml new file mode 100644 index 0000000..29d368d --- /dev/null +++ b/pymavlink/dialects/v10/matrixpilot.xml @@ -0,0 +1,284 @@ + + + common.xml + + + + + + + + Action required when performing CMD_PREFLIGHT_STORAGE + + Read all parameters from storage + + + Write all parameters to storage + + + Clear all parameters in storage + + + Read specific parameters from storage + + + Write specific parameters to storage + + + Clear specific parameters in storage + + + do nothing + + + + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED + Storage area as defined by parameter database + Storage flags as defined by parameter database + Empty + Empty + Empty + Empty + + + + + + + + + Depreciated but used as a compiler flag. Do not remove + System ID + Component ID + + + Reqest reading of flexifunction data + System ID + Component ID + Type of flexifunction data requested + index into data where needed + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + Total count of functions + Address in the flexifunction data, Set to 0xFFFF to use address in target memory + Size of the + Settings data + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + Settings data + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + Flexifunction command type + + + Acknowldge sucess or failure of a flexifunction command + Command acknowledged + result of acknowledge + + + Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A + Serial UDB Extra Time + Serial UDB Extra Status + Serial UDB Extra Latitude + Serial UDB Extra Longitude + Serial UDB Extra Altitude + Serial UDB Extra Waypoint Index + Serial UDB Extra Rmat 0 + Serial UDB Extra Rmat 1 + Serial UDB Extra Rmat 2 + Serial UDB Extra Rmat 3 + Serial UDB Extra Rmat 4 + Serial UDB Extra Rmat 5 + Serial UDB Extra Rmat 6 + Serial UDB Extra Rmat 7 + Serial UDB Extra Rmat 8 + Serial UDB Extra GPS Course Over Ground + Serial UDB Extra Speed Over Ground + Serial UDB Extra CPU Load + Serial UDB Extra Voltage in MilliVolts + Serial UDB Extra 3D IMU Air Speed + Serial UDB Extra Estimated Wind 0 + Serial UDB Extra Estimated Wind 1 + Serial UDB Extra Estimated Wind 2 + Serial UDB Extra Magnetic Field Earth 0 + Serial UDB Extra Magnetic Field Earth 1 + Serial UDB Extra Magnetic Field Earth 2 + Serial UDB Extra Number of Sattelites in View + Serial UDB Extra GPS Horizontal Dilution of Precision + + + Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B + Serial UDB Extra Time + Serial UDB Extra PWM Input Channel 1 + Serial UDB Extra PWM Input Channel 2 + Serial UDB Extra PWM Input Channel 3 + Serial UDB Extra PWM Input Channel 4 + Serial UDB Extra PWM Input Channel 5 + Serial UDB Extra PWM Input Channel 6 + Serial UDB Extra PWM Input Channel 7 + Serial UDB Extra PWM Input Channel 8 + Serial UDB Extra PWM Input Channel 9 + Serial UDB Extra PWM Input Channel 10 + Serial UDB Extra PWM Output Channel 1 + Serial UDB Extra PWM Output Channel 2 + Serial UDB Extra PWM Output Channel 3 + Serial UDB Extra PWM Output Channel 4 + Serial UDB Extra PWM Output Channel 5 + Serial UDB Extra PWM Output Channel 6 + Serial UDB Extra PWM Output Channel 7 + Serial UDB Extra PWM Output Channel 8 + Serial UDB Extra PWM Output Channel 9 + Serial UDB Extra PWM Output Channel 10 + Serial UDB Extra IMU Location X + Serial UDB Extra IMU Location Y + Serial UDB Extra IMU Location Z + Serial UDB Extra Status Flags + Serial UDB Extra Oscillator Failure Count + Serial UDB Extra IMU Velocity X + Serial UDB Extra IMU Velocity Y + Serial UDB Extra IMU Velocity Z + Serial UDB Extra Current Waypoint Goal X + Serial UDB Extra Current Waypoint Goal Y + Serial UDB Extra Current Waypoint Goal Z + Serial UDB Extra Stack Memory Free + + + Backwards compatible version of SERIAL_UDB_EXTRA F4: format + Serial UDB Extra Roll Stabilization with Ailerons Enabled + Serial UDB Extra Roll Stabilization with Rudder Enabled + Serial UDB Extra Pitch Stabilization Enabled + Serial UDB Extra Yaw Stabilization using Rudder Enabled + Serial UDB Extra Yaw Stabilization using Ailerons Enabled + Serial UDB Extra Navigation with Ailerons Enabled + Serial UDB Extra Navigation with Rudder Enabled + Serial UDB Extra Type of Alitude Hold when in Stabilized Mode + Serial UDB Extra Type of Alitude Hold when in Waypoint Mode + Serial UDB Extra Firmware racing mode enabled + + + Backwards compatible version of SERIAL_UDB_EXTRA F5: format + Serial UDB YAWKP_AILERON Gain for Proporional control of navigation + Serial UDB YAWKD_AILERON Gain for Rate control of navigation + Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization + YAW_STABILIZATION_AILERON Proportional control + Gain For Boosting Manual Aileron control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F6: format + Serial UDB Extra PITCHGAIN Proportional Control + Serial UDB Extra Pitch Rate Control + Serial UDB Extra Rudder to Elevator Mix + Serial UDB Extra Roll to Elevator Mix + Gain For Boosting Manual Elevator control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F7: format + Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation + Serial UDB YAWKD_RUDDER Gain for Rate control of navigation + Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization + SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized + Serial UDB Extra Return To Landing - Angle to Pitch Plane Down + + + Backwards compatible version of SERIAL_UDB_EXTRA F8: format + Serial UDB Extra HEIGHT_TARGET_MAX + Serial UDB Extra HEIGHT_TARGET_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MAX + Serial UDB Extra ALT_HOLD_PITCH_MIN + Serial UDB Extra ALT_HOLD_PITCH_MAX + Serial UDB Extra ALT_HOLD_PITCH_HIGH + + + Backwards compatible version of SERIAL_UDB_EXTRA F13: format + Serial UDB Extra GPS Week Number + Serial UDB Extra MP Origin Latitude + Serial UDB Extra MP Origin Longitude + Serial UDB Extra MP Origin Altitude Above Sea Level + + + Backwards compatible version of SERIAL_UDB_EXTRA F14: format + Serial UDB Extra Wind Estimation Enabled + Serial UDB Extra Type of GPS Unit + Serial UDB Extra Dead Reckoning Enabled + Serial UDB Extra Type of UDB Hardware + Serial UDB Extra Type of Airframe + Serial UDB Extra Reboot Regitster of DSPIC + Serial UDB Extra Last dspic Trap Flags + Serial UDB Extra Type Program Address of Last Trap + Serial UDB Extra Number of Ocillator Failures + Serial UDB Extra UDB Internal Clock Configuration + Serial UDB Extra Type of Flight Plan + + + Backwards compatible version of SERIAL_UDB_EXTRA F15 and F16: format + Serial UDB Extra Model Name Of Vehicle + Serial UDB Extra Registraton Number of Vehicle + + + Serial UDB Extra Name of Expected Lead Pilot + Serial UDB Extra URL of Lead Pilot or Team + + + The altitude measured by sensors and IMU + Timestamp (milliseconds since system boot) + GPS altitude in meters, expressed as * 1000 (millimeters), above MSL + IMU altitude above ground in meters, expressed as * 1000 (millimeters) + barometeric altitude above ground in meters, expressed as * 1000 (millimeters) + Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) + Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) + Extra altitude above ground in meters, expressed as * 1000 (millimeters) + + + The airspeed measured by sensors and IMU + Timestamp (milliseconds since system boot) + Airspeed estimate from IMU, cm/s + Pitot measured forward airpseed, cm/s + Hot wire anenometer measured airspeed, cm/s + Ultrasonic measured airspeed, cm/s + Angle of attack sensor, degrees * 10 + Yaw angle sensor, degrees * 10 + + + + diff --git a/pymavlink/dialects/v10/minimal.py b/pymavlink/dialects/v10/minimal.py new file mode 100644 index 0000000..4028123 --- /dev/null +++ b/pymavlink/dialects/v10/minimal.py @@ -0,0 +1,643 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: minimal.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "minimal" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack('= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + + 2 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + PIXHAWK autopilot, http://pixhawk.ethz.ch + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version + + + diff --git a/pymavlink/dialects/v10/paparazzi.py b/pymavlink/dialects/v10/paparazzi.py new file mode 100644 index 0000000..b968711 --- /dev/null +++ b/pymavlink/dialects/v10/paparazzi.py @@ -0,0 +1,11193 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: paparazzi.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "paparazzi" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_SCRIPT_ITEM = 180 +MAVLINK_MSG_ID_SCRIPT_REQUEST = 181 +MAVLINK_MSG_ID_SCRIPT_REQUEST_LIST = 182 +MAVLINK_MSG_ID_SCRIPT_COUNT = 183 +MAVLINK_MSG_ID_SCRIPT_CURRENT = 184 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_script_item_message(MAVLink_message): + ''' + Message encoding a mission script item. This message is + emitted upon a request for the next script item. + ''' + id = MAVLINK_MSG_ID_SCRIPT_ITEM + name = 'SCRIPT_ITEM' + fieldnames = ['target_system', 'target_component', 'seq', 'name'] + ordered_fieldnames = [ 'seq', 'target_system', 'target_component', 'name' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/paparazzi.xml b/pymavlink/dialects/v10/paparazzi.xml new file mode 100755 index 0000000..2200075 --- /dev/null +++ b/pymavlink/dialects/v10/paparazzi.xml @@ -0,0 +1,38 @@ + + + common.xml + 3 + + + + + + Message encoding a mission script item. This message is emitted upon a request for the next script item. + System ID + Component ID + Sequence + The name of the mission script, NULL terminated. + + + Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. + System ID + Component ID + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. + System ID + Component ID + Number of script items in the sequence + + + This message informs about the currently active SCRIPT. + Active Sequence + + + diff --git a/pymavlink/dialects/v10/python_array_test.py b/pymavlink/dialects/v10/python_array_test.py new file mode 100644 index 0000000..6a73728 --- /dev/null +++ b/pymavlink/dialects/v10/python_array_test.py @@ -0,0 +1,11370 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: python_array_test.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "python_array_test" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_ARRAY_TEST_0 = 150 +MAVLINK_MSG_ID_ARRAY_TEST_1 = 151 +MAVLINK_MSG_ID_ARRAY_TEST_3 = 153 +MAVLINK_MSG_ID_ARRAY_TEST_4 = 154 +MAVLINK_MSG_ID_ARRAY_TEST_5 = 155 +MAVLINK_MSG_ID_ARRAY_TEST_6 = 156 +MAVLINK_MSG_ID_ARRAY_TEST_7 = 157 +MAVLINK_MSG_ID_ARRAY_TEST_8 = 158 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_array_test_0_message(MAVLink_message): + ''' + Array test #0. + ''' + id = MAVLINK_MSG_ID_ARRAY_TEST_0 + name = 'ARRAY_TEST_0' + fieldnames = ['v1', 'ar_i8', 'ar_u8', 'ar_u16', 'ar_u32'] + ordered_fieldnames = [ 'ar_u32', 'ar_u16', 'v1', 'ar_i8', 'ar_u8' ] + format = '<4I4HB4b4B' + native_format = bytearray(' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/python_array_test.xml b/pymavlink/dialects/v10/python_array_test.xml new file mode 100644 index 0000000..f230d01 --- /dev/null +++ b/pymavlink/dialects/v10/python_array_test.xml @@ -0,0 +1,67 @@ + + + +common.xml + + + Array test #0. + Stub field + Value array + Value array + Value array + Value array + + + Array test #1. + Value array + + + Array test #3. + Stub field + Value array + + + Array test #4. + Value array + Stub field + + + Array test #5. + Value array + Value array + + + Array test #6. + Stub field + Stub field + Stub field + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #7. + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #8. + Stub field + Value array + Value array + + + diff --git a/pymavlink/dialects/v10/satball.py b/pymavlink/dialects/v10/satball.py new file mode 100644 index 0000000..fce2f9e --- /dev/null +++ b/pymavlink/dialects/v10/satball.py @@ -0,0 +1,11052 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: satball.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "satball" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_SATBALL_SENS = 150 +MAVLINK_MSG_ID_MOTOR_PWM = 151 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_satball_sens_message(MAVLink_message): + ''' + This message encodes all the motor RPM measurments form the + actuator board + ''' + id = MAVLINK_MSG_ID_SATBALL_SENS + name = 'SATBALL_SENS' + fieldnames = ['time_usec', 'acc', 'gyro', 'mag', 'rpm_vect'] + ordered_fieldnames = [ 'time_usec', 'acc', 'gyro', 'mag', 'rpm_vect' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/satball.xml b/pymavlink/dialects/v10/satball.xml new file mode 100644 index 0000000..3392f08 --- /dev/null +++ b/pymavlink/dialects/v10/satball.xml @@ -0,0 +1,24 @@ + + + common.xml + + + + + + + This message encodes all the motor RPM measurments form the actuator board + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + This vector contains imu_acc [ax ay az] + This vector contains imu_gyro [gx gy gz] + This vector contains imu_mag [mx my mz] + This vector contains all the rpm values for each motor [m1 m2 m3 m4] + + + This message encodes all the motor driver values for the motors in the tetrahedron configuration + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Can take the value between 0x00 to 0xFFFF [m1 m2 m3 m4] + Can take the value between 0x00 to 0xFFFF [magx magy magz] + + + diff --git a/pymavlink/dialects/v10/satball_old.py b/pymavlink/dialects/v10/satball_old.py new file mode 100644 index 0000000..8776243 --- /dev/null +++ b/pymavlink/dialects/v10/satball_old.py @@ -0,0 +1,11058 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: satball_old.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "satball_old" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_RPM_RAW = 150 +MAVLINK_MSG_ID_MOTOR_PWM = 151 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_rpm_raw_message(MAVLink_message): + ''' + This message encodes all the motor RPM measurments form the + actuator board + ''' + id = MAVLINK_MSG_ID_RPM_RAW + name = 'RPM_RAW' + fieldnames = ['time_usec', 'rpm_motor1', 'rpm_motor2', 'rpm_motor3', 'rpm_motor4'] + ordered_fieldnames = [ 'time_usec', 'rpm_motor1', 'rpm_motor2', 'rpm_motor3', 'rpm_motor4' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/satball_old.xml b/pymavlink/dialects/v10/satball_old.xml new file mode 100644 index 0000000..463eb47 --- /dev/null +++ b/pymavlink/dialects/v10/satball_old.xml @@ -0,0 +1,26 @@ + + + common.xml + + + + + + + This message encodes all the motor RPM measurments form the actuator board + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + + + + + + + This message encodes all the motor driver values for the motors in the tetrahedron configuration + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Can take the value between 0x00 to 0xFF + Can take the value between 0x00 to 0xFF + Can take the value between 0x00 to 0xFF + Can take the value between 0x00 to 0xFF + + + diff --git a/pymavlink/dialects/v10/slugs.py b/pymavlink/dialects/v10/slugs.py new file mode 100644 index 0000000..b614d3c --- /dev/null +++ b/pymavlink/dialects/v10/slugs.py @@ -0,0 +1,12139 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: slugs.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "slugs" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_DO_NOTHING = 10001 # Does nothing. +enums['MAV_CMD'][10001] = EnumEntry('MAV_CMD_DO_NOTHING', '''Does nothing.''') +enums['MAV_CMD'][10001].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_RETURN_TO_BASE = 10011 # Return vehicle to base. +enums['MAV_CMD'][10011] = EnumEntry('MAV_CMD_RETURN_TO_BASE', '''Return vehicle to base.''') +enums['MAV_CMD'][10011].param[1] = '''0: return to base, 1: track mobile base''' +MAV_CMD_STOP_RETURN_TO_BASE = 10012 # Stops the vehicle from returning to base and resumes flight. +enums['MAV_CMD'][10012] = EnumEntry('MAV_CMD_STOP_RETURN_TO_BASE', '''Stops the vehicle from returning to base and resumes flight. ''') +MAV_CMD_TURN_LIGHT = 10013 # Turns the vehicle's visible or infrared lights on or off. +enums['MAV_CMD'][10013] = EnumEntry('MAV_CMD_TURN_LIGHT', '''Turns the vehicle's visible or infrared lights on or off.''') +enums['MAV_CMD'][10013].param[1] = '''0: visible lights, 1: infrared lights''' +enums['MAV_CMD'][10013].param[2] = '''0: turn on, 1: turn off''' +MAV_CMD_GET_MID_LEVEL_COMMANDS = 10014 # Requests vehicle to send current mid-level commands to ground station. +enums['MAV_CMD'][10014] = EnumEntry('MAV_CMD_GET_MID_LEVEL_COMMANDS', '''Requests vehicle to send current mid-level commands to ground station.''') +MAV_CMD_MIDLEVEL_STORAGE = 10015 # Requests storage of mid-level commands. +enums['MAV_CMD'][10015] = EnumEntry('MAV_CMD_MIDLEVEL_STORAGE', '''Requests storage of mid-level commands.''') +enums['MAV_CMD'][10015].param[1] = '''Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# SLUGS_MODE +enums['SLUGS_MODE'] = {} +SLUGS_MODE_NONE = 0 # No change to SLUGS mode. +enums['SLUGS_MODE'][0] = EnumEntry('SLUGS_MODE_NONE', '''No change to SLUGS mode.''') +SLUGS_MODE_LIFTOFF = 1 # Vehicle is in liftoff mode. +enums['SLUGS_MODE'][1] = EnumEntry('SLUGS_MODE_LIFTOFF', '''Vehicle is in liftoff mode.''') +SLUGS_MODE_PASSTHROUGH = 2 # Vehicle is in passthrough mode, being controlled by a pilot. +enums['SLUGS_MODE'][2] = EnumEntry('SLUGS_MODE_PASSTHROUGH', '''Vehicle is in passthrough mode, being controlled by a pilot.''') +SLUGS_MODE_WAYPOINT = 3 # Vehicle is in waypoint mode, navigating to waypoints. +enums['SLUGS_MODE'][3] = EnumEntry('SLUGS_MODE_WAYPOINT', '''Vehicle is in waypoint mode, navigating to waypoints.''') +SLUGS_MODE_MID_LEVEL = 4 # Vehicle is executing mid-level commands. +enums['SLUGS_MODE'][4] = EnumEntry('SLUGS_MODE_MID_LEVEL', '''Vehicle is executing mid-level commands.''') +SLUGS_MODE_RETURNING = 5 # Vehicle is returning to the home location. +enums['SLUGS_MODE'][5] = EnumEntry('SLUGS_MODE_RETURNING', '''Vehicle is returning to the home location.''') +SLUGS_MODE_LANDING = 6 # Vehicle is landing. +enums['SLUGS_MODE'][6] = EnumEntry('SLUGS_MODE_LANDING', '''Vehicle is landing.''') +SLUGS_MODE_LOST = 7 # Lost connection with vehicle. +enums['SLUGS_MODE'][7] = EnumEntry('SLUGS_MODE_LOST', '''Lost connection with vehicle.''') +SLUGS_MODE_SELECTIVE_PASSTHROUGH = 8 # Vehicle is in selective passthrough mode, where selected surfaces are + # being manually controlled. +enums['SLUGS_MODE'][8] = EnumEntry('SLUGS_MODE_SELECTIVE_PASSTHROUGH', '''Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled.''') +SLUGS_MODE_ISR = 9 # Vehicle is in ISR mode, performing reconaissance at a point specified + # by ISR_LOCATION message. +enums['SLUGS_MODE'][9] = EnumEntry('SLUGS_MODE_ISR', '''Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message.''') +SLUGS_MODE_LINE_PATROL = 10 # Vehicle is patrolling along lines between waypoints. +enums['SLUGS_MODE'][10] = EnumEntry('SLUGS_MODE_LINE_PATROL', '''Vehicle is patrolling along lines between waypoints.''') +SLUGS_MODE_GROUNDED = 11 # Vehicle is grounded or an error has occurred. +enums['SLUGS_MODE'][11] = EnumEntry('SLUGS_MODE_GROUNDED', '''Vehicle is grounded or an error has occurred.''') +SLUGS_MODE_ENUM_END = 12 # +enums['SLUGS_MODE'][12] = EnumEntry('SLUGS_MODE_ENUM_END', '''''') + +# CONTROL_SURFACE_FLAG +enums['CONTROL_SURFACE_FLAG'] = {} +CONTROL_SURFACE_FLAG_RIGHT_FLAP = 1 # 0b00000001 Right flap control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][1] = EnumEntry('CONTROL_SURFACE_FLAG_RIGHT_FLAP', '''0b00000001 Right flap control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_LEFT_FLAP = 2 # 0b00000010 Left flap control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][2] = EnumEntry('CONTROL_SURFACE_FLAG_LEFT_FLAP', '''0b00000010 Left flap control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR = 4 # 0b00000100 Right elevator control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][4] = EnumEntry('CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR', '''0b00000100 Right elevator control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_LEFT_ELEVATOR = 8 # 0b00001000 Left elevator control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][8] = EnumEntry('CONTROL_SURFACE_FLAG_LEFT_ELEVATOR', '''0b00001000 Left elevator control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_RUDDER = 16 # 0b00010000 Rudder control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][16] = EnumEntry('CONTROL_SURFACE_FLAG_RUDDER', '''0b00010000 Rudder control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_RIGHT_AILERON = 32 # 0b00100000 Right aileron control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][32] = EnumEntry('CONTROL_SURFACE_FLAG_RIGHT_AILERON', '''0b00100000 Right aileron control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_LEFT_AILERON = 64 # 0b01000000 Left aileron control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][64] = EnumEntry('CONTROL_SURFACE_FLAG_LEFT_AILERON', '''0b01000000 Left aileron control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_THROTTLE = 128 # 0b10000000 Throttle control passes through to pilot console. +enums['CONTROL_SURFACE_FLAG'][128] = EnumEntry('CONTROL_SURFACE_FLAG_THROTTLE', '''0b10000000 Throttle control passes through to pilot console.''') +CONTROL_SURFACE_FLAG_ENUM_END = 129 # +enums['CONTROL_SURFACE_FLAG'][129] = EnumEntry('CONTROL_SURFACE_FLAG_ENUM_END', '''''') + +# MAV_AUTOPILOT +enums['MAV_AUTOPILOT'] = {} +MAV_AUTOPILOT_GENERIC = 0 # Generic autopilot, full support for everything +enums['MAV_AUTOPILOT'][0] = EnumEntry('MAV_AUTOPILOT_GENERIC', '''Generic autopilot, full support for everything''') +MAV_AUTOPILOT_RESERVED = 1 # Reserved for future use. +enums['MAV_AUTOPILOT'][1] = EnumEntry('MAV_AUTOPILOT_RESERVED', '''Reserved for future use.''') +MAV_AUTOPILOT_SLUGS = 2 # SLUGS autopilot, http://slugsuav.soe.ucsc.edu +enums['MAV_AUTOPILOT'][2] = EnumEntry('MAV_AUTOPILOT_SLUGS', '''SLUGS autopilot, http://slugsuav.soe.ucsc.edu''') +MAV_AUTOPILOT_ARDUPILOTMEGA = 3 # ArduPilotMega / ArduCopter, http://diydrones.com +enums['MAV_AUTOPILOT'][3] = EnumEntry('MAV_AUTOPILOT_ARDUPILOTMEGA', '''ArduPilotMega / ArduCopter, http://diydrones.com''') +MAV_AUTOPILOT_OPENPILOT = 4 # OpenPilot, http://openpilot.org +enums['MAV_AUTOPILOT'][4] = EnumEntry('MAV_AUTOPILOT_OPENPILOT', '''OpenPilot, http://openpilot.org''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5 # Generic autopilot only supporting simple waypoints +enums['MAV_AUTOPILOT'][5] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY', '''Generic autopilot only supporting simple waypoints''') +MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6 # Generic autopilot supporting waypoints and other simple navigation + # commands +enums['MAV_AUTOPILOT'][6] = EnumEntry('MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY', '''Generic autopilot supporting waypoints and other simple navigation commands''') +MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7 # Generic autopilot supporting the full mission command set +enums['MAV_AUTOPILOT'][7] = EnumEntry('MAV_AUTOPILOT_GENERIC_MISSION_FULL', '''Generic autopilot supporting the full mission command set''') +MAV_AUTOPILOT_INVALID = 8 # No valid autopilot, e.g. a GCS or other MAVLink component +enums['MAV_AUTOPILOT'][8] = EnumEntry('MAV_AUTOPILOT_INVALID', '''No valid autopilot, e.g. a GCS or other MAVLink component''') +MAV_AUTOPILOT_PPZ = 9 # PPZ UAV - http://nongnu.org/paparazzi +enums['MAV_AUTOPILOT'][9] = EnumEntry('MAV_AUTOPILOT_PPZ', '''PPZ UAV - http://nongnu.org/paparazzi''') +MAV_AUTOPILOT_UDB = 10 # UAV Dev Board +enums['MAV_AUTOPILOT'][10] = EnumEntry('MAV_AUTOPILOT_UDB', '''UAV Dev Board''') +MAV_AUTOPILOT_FP = 11 # FlexiPilot +enums['MAV_AUTOPILOT'][11] = EnumEntry('MAV_AUTOPILOT_FP', '''FlexiPilot''') +MAV_AUTOPILOT_PX4 = 12 # PX4 Autopilot - http://pixhawk.ethz.ch/px4/ +enums['MAV_AUTOPILOT'][12] = EnumEntry('MAV_AUTOPILOT_PX4', '''PX4 Autopilot - http://pixhawk.ethz.ch/px4/''') +MAV_AUTOPILOT_SMACCMPILOT = 13 # SMACCMPilot - http://smaccmpilot.org +enums['MAV_AUTOPILOT'][13] = EnumEntry('MAV_AUTOPILOT_SMACCMPILOT', '''SMACCMPilot - http://smaccmpilot.org''') +MAV_AUTOPILOT_AUTOQUAD = 14 # AutoQuad -- http://autoquad.org +enums['MAV_AUTOPILOT'][14] = EnumEntry('MAV_AUTOPILOT_AUTOQUAD', '''AutoQuad -- http://autoquad.org''') +MAV_AUTOPILOT_ARMAZILA = 15 # Armazila -- http://armazila.com +enums['MAV_AUTOPILOT'][15] = EnumEntry('MAV_AUTOPILOT_ARMAZILA', '''Armazila -- http://armazila.com''') +MAV_AUTOPILOT_AEROB = 16 # Aerob -- http://aerob.ru +enums['MAV_AUTOPILOT'][16] = EnumEntry('MAV_AUTOPILOT_AEROB', '''Aerob -- http://aerob.ru''') +MAV_AUTOPILOT_ASLUAV = 17 # ASLUAV autopilot -- http://www.asl.ethz.ch +enums['MAV_AUTOPILOT'][17] = EnumEntry('MAV_AUTOPILOT_ASLUAV', '''ASLUAV autopilot -- http://www.asl.ethz.ch''') +MAV_AUTOPILOT_ENUM_END = 18 # +enums['MAV_AUTOPILOT'][18] = EnumEntry('MAV_AUTOPILOT_ENUM_END', '''''') + +# MAV_TYPE +enums['MAV_TYPE'] = {} +MAV_TYPE_GENERIC = 0 # Generic micro air vehicle. +enums['MAV_TYPE'][0] = EnumEntry('MAV_TYPE_GENERIC', '''Generic micro air vehicle.''') +MAV_TYPE_FIXED_WING = 1 # Fixed wing aircraft. +enums['MAV_TYPE'][1] = EnumEntry('MAV_TYPE_FIXED_WING', '''Fixed wing aircraft.''') +MAV_TYPE_QUADROTOR = 2 # Quadrotor +enums['MAV_TYPE'][2] = EnumEntry('MAV_TYPE_QUADROTOR', '''Quadrotor''') +MAV_TYPE_COAXIAL = 3 # Coaxial helicopter +enums['MAV_TYPE'][3] = EnumEntry('MAV_TYPE_COAXIAL', '''Coaxial helicopter''') +MAV_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor. +enums['MAV_TYPE'][4] = EnumEntry('MAV_TYPE_HELICOPTER', '''Normal helicopter with tail rotor.''') +MAV_TYPE_ANTENNA_TRACKER = 5 # Ground installation +enums['MAV_TYPE'][5] = EnumEntry('MAV_TYPE_ANTENNA_TRACKER', '''Ground installation''') +MAV_TYPE_GCS = 6 # Operator control unit / ground control station +enums['MAV_TYPE'][6] = EnumEntry('MAV_TYPE_GCS', '''Operator control unit / ground control station''') +MAV_TYPE_AIRSHIP = 7 # Airship, controlled +enums['MAV_TYPE'][7] = EnumEntry('MAV_TYPE_AIRSHIP', '''Airship, controlled''') +MAV_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled +enums['MAV_TYPE'][8] = EnumEntry('MAV_TYPE_FREE_BALLOON', '''Free balloon, uncontrolled''') +MAV_TYPE_ROCKET = 9 # Rocket +enums['MAV_TYPE'][9] = EnumEntry('MAV_TYPE_ROCKET', '''Rocket''') +MAV_TYPE_GROUND_ROVER = 10 # Ground rover +enums['MAV_TYPE'][10] = EnumEntry('MAV_TYPE_GROUND_ROVER', '''Ground rover''') +MAV_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship +enums['MAV_TYPE'][11] = EnumEntry('MAV_TYPE_SURFACE_BOAT', '''Surface vessel, boat, ship''') +MAV_TYPE_SUBMARINE = 12 # Submarine +enums['MAV_TYPE'][12] = EnumEntry('MAV_TYPE_SUBMARINE', '''Submarine''') +MAV_TYPE_HEXAROTOR = 13 # Hexarotor +enums['MAV_TYPE'][13] = EnumEntry('MAV_TYPE_HEXAROTOR', '''Hexarotor''') +MAV_TYPE_OCTOROTOR = 14 # Octorotor +enums['MAV_TYPE'][14] = EnumEntry('MAV_TYPE_OCTOROTOR', '''Octorotor''') +MAV_TYPE_TRICOPTER = 15 # Octorotor +enums['MAV_TYPE'][15] = EnumEntry('MAV_TYPE_TRICOPTER', '''Octorotor''') +MAV_TYPE_FLAPPING_WING = 16 # Flapping wing +enums['MAV_TYPE'][16] = EnumEntry('MAV_TYPE_FLAPPING_WING', '''Flapping wing''') +MAV_TYPE_KITE = 17 # Flapping wing +enums['MAV_TYPE'][17] = EnumEntry('MAV_TYPE_KITE', '''Flapping wing''') +MAV_TYPE_ONBOARD_CONTROLLER = 18 # Onboard companion controller +enums['MAV_TYPE'][18] = EnumEntry('MAV_TYPE_ONBOARD_CONTROLLER', '''Onboard companion controller''') +MAV_TYPE_VTOL_DUOROTOR = 19 # Two-rotor VTOL using control surfaces in vertical operation in + # addition. Tailsitter. +enums['MAV_TYPE'][19] = EnumEntry('MAV_TYPE_VTOL_DUOROTOR', '''Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.''') +MAV_TYPE_VTOL_QUADROTOR = 20 # Quad-rotor VTOL using a V-shaped quad config in vertical operation. + # Tailsitter. +enums['MAV_TYPE'][20] = EnumEntry('MAV_TYPE_VTOL_QUADROTOR', '''Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.''') +MAV_TYPE_VTOL_TILTROTOR = 21 # Tiltrotor VTOL +enums['MAV_TYPE'][21] = EnumEntry('MAV_TYPE_VTOL_TILTROTOR', '''Tiltrotor VTOL''') +MAV_TYPE_VTOL_RESERVED2 = 22 # VTOL reserved 2 +enums['MAV_TYPE'][22] = EnumEntry('MAV_TYPE_VTOL_RESERVED2', '''VTOL reserved 2''') +MAV_TYPE_VTOL_RESERVED3 = 23 # VTOL reserved 3 +enums['MAV_TYPE'][23] = EnumEntry('MAV_TYPE_VTOL_RESERVED3', '''VTOL reserved 3''') +MAV_TYPE_VTOL_RESERVED4 = 24 # VTOL reserved 4 +enums['MAV_TYPE'][24] = EnumEntry('MAV_TYPE_VTOL_RESERVED4', '''VTOL reserved 4''') +MAV_TYPE_VTOL_RESERVED5 = 25 # VTOL reserved 5 +enums['MAV_TYPE'][25] = EnumEntry('MAV_TYPE_VTOL_RESERVED5', '''VTOL reserved 5''') +MAV_TYPE_GIMBAL = 26 # Onboard gimbal +enums['MAV_TYPE'][26] = EnumEntry('MAV_TYPE_GIMBAL', '''Onboard gimbal''') +MAV_TYPE_ADSB = 27 # Onboard ADSB peripheral +enums['MAV_TYPE'][27] = EnumEntry('MAV_TYPE_ADSB', '''Onboard ADSB peripheral''') +MAV_TYPE_ENUM_END = 28 # +enums['MAV_TYPE'][28] = EnumEntry('MAV_TYPE_ENUM_END', '''''') + +# FIRMWARE_VERSION_TYPE +enums['FIRMWARE_VERSION_TYPE'] = {} +FIRMWARE_VERSION_TYPE_DEV = 0 # development release +enums['FIRMWARE_VERSION_TYPE'][0] = EnumEntry('FIRMWARE_VERSION_TYPE_DEV', '''development release''') +FIRMWARE_VERSION_TYPE_ALPHA = 64 # alpha release +enums['FIRMWARE_VERSION_TYPE'][64] = EnumEntry('FIRMWARE_VERSION_TYPE_ALPHA', '''alpha release''') +FIRMWARE_VERSION_TYPE_BETA = 128 # beta release +enums['FIRMWARE_VERSION_TYPE'][128] = EnumEntry('FIRMWARE_VERSION_TYPE_BETA', '''beta release''') +FIRMWARE_VERSION_TYPE_RC = 192 # release candidate +enums['FIRMWARE_VERSION_TYPE'][192] = EnumEntry('FIRMWARE_VERSION_TYPE_RC', '''release candidate''') +FIRMWARE_VERSION_TYPE_OFFICIAL = 255 # official stable release +enums['FIRMWARE_VERSION_TYPE'][255] = EnumEntry('FIRMWARE_VERSION_TYPE_OFFICIAL', '''official stable release''') +FIRMWARE_VERSION_TYPE_ENUM_END = 256 # +enums['FIRMWARE_VERSION_TYPE'][256] = EnumEntry('FIRMWARE_VERSION_TYPE_ENUM_END', '''''') + +# MAV_MODE_FLAG +enums['MAV_MODE_FLAG'] = {} +MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 # 0b00000001 Reserved for future use. +enums['MAV_MODE_FLAG'][1] = EnumEntry('MAV_MODE_FLAG_CUSTOM_MODE_ENABLED', '''0b00000001 Reserved for future use.''') +MAV_MODE_FLAG_TEST_ENABLED = 2 # 0b00000010 system has a test mode enabled. This flag is intended for + # temporary system tests and should not be + # used for stable implementations. +enums['MAV_MODE_FLAG'][2] = EnumEntry('MAV_MODE_FLAG_TEST_ENABLED', '''0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.''') +MAV_MODE_FLAG_AUTO_ENABLED = 4 # 0b00000100 autonomous mode enabled, system finds its own goal + # positions. Guided flag can be set or not, + # depends on the actual implementation. +enums['MAV_MODE_FLAG'][4] = EnumEntry('MAV_MODE_FLAG_AUTO_ENABLED', '''0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.''') +MAV_MODE_FLAG_GUIDED_ENABLED = 8 # 0b00001000 guided mode enabled, system flies MISSIONs / mission items. +enums['MAV_MODE_FLAG'][8] = EnumEntry('MAV_MODE_FLAG_GUIDED_ENABLED', '''0b00001000 guided mode enabled, system flies MISSIONs / mission items.''') +MAV_MODE_FLAG_STABILIZE_ENABLED = 16 # 0b00010000 system stabilizes electronically its attitude (and + # optionally position). It needs however + # further control inputs to move around. +enums['MAV_MODE_FLAG'][16] = EnumEntry('MAV_MODE_FLAG_STABILIZE_ENABLED', '''0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.''') +MAV_MODE_FLAG_HIL_ENABLED = 32 # 0b00100000 hardware in the loop simulation. All motors / actuators are + # blocked, but internal software is full + # operational. +enums['MAV_MODE_FLAG'][32] = EnumEntry('MAV_MODE_FLAG_HIL_ENABLED', '''0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.''') +MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 # 0b01000000 remote control input is enabled. +enums['MAV_MODE_FLAG'][64] = EnumEntry('MAV_MODE_FLAG_MANUAL_INPUT_ENABLED', '''0b01000000 remote control input is enabled.''') +MAV_MODE_FLAG_SAFETY_ARMED = 128 # 0b10000000 MAV safety set to armed. Motors are enabled / running / can + # start. Ready to fly. +enums['MAV_MODE_FLAG'][128] = EnumEntry('MAV_MODE_FLAG_SAFETY_ARMED', '''0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.''') +MAV_MODE_FLAG_ENUM_END = 129 # +enums['MAV_MODE_FLAG'][129] = EnumEntry('MAV_MODE_FLAG_ENUM_END', '''''') + +# MAV_MODE_FLAG_DECODE_POSITION +enums['MAV_MODE_FLAG_DECODE_POSITION'] = {} +MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1 # Eighth bit: 00000001 +enums['MAV_MODE_FLAG_DECODE_POSITION'][1] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE', '''Eighth bit: 00000001''') +MAV_MODE_FLAG_DECODE_POSITION_TEST = 2 # Seventh bit: 00000010 +enums['MAV_MODE_FLAG_DECODE_POSITION'][2] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_TEST', '''Seventh bit: 00000010''') +MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4 # Sixt bit: 00000100 +enums['MAV_MODE_FLAG_DECODE_POSITION'][4] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_AUTO', '''Sixt bit: 00000100''') +MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8 # Fifth bit: 00001000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][8] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_GUIDED', '''Fifth bit: 00001000''') +MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16 # Fourth bit: 00010000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][16] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_STABILIZE', '''Fourth bit: 00010000''') +MAV_MODE_FLAG_DECODE_POSITION_HIL = 32 # Third bit: 00100000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][32] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_HIL', '''Third bit: 00100000''') +MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64 # Second bit: 01000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][64] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_MANUAL', '''Second bit: 01000000''') +MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128 # First bit: 10000000 +enums['MAV_MODE_FLAG_DECODE_POSITION'][128] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_SAFETY', '''First bit: 10000000''') +MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129 # +enums['MAV_MODE_FLAG_DECODE_POSITION'][129] = EnumEntry('MAV_MODE_FLAG_DECODE_POSITION_ENUM_END', '''''') + +# MAV_GOTO +enums['MAV_GOTO'] = {} +MAV_GOTO_DO_HOLD = 0 # Hold at the current position. +enums['MAV_GOTO'][0] = EnumEntry('MAV_GOTO_DO_HOLD', '''Hold at the current position.''') +MAV_GOTO_DO_CONTINUE = 1 # Continue with the next item in mission execution. +enums['MAV_GOTO'][1] = EnumEntry('MAV_GOTO_DO_CONTINUE', '''Continue with the next item in mission execution.''') +MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2 # Hold at the current position of the system +enums['MAV_GOTO'][2] = EnumEntry('MAV_GOTO_HOLD_AT_CURRENT_POSITION', '''Hold at the current position of the system''') +MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 # Hold at the position specified in the parameters of the DO_HOLD action +enums['MAV_GOTO'][3] = EnumEntry('MAV_GOTO_HOLD_AT_SPECIFIED_POSITION', '''Hold at the position specified in the parameters of the DO_HOLD action''') +MAV_GOTO_ENUM_END = 4 # +enums['MAV_GOTO'][4] = EnumEntry('MAV_GOTO_ENUM_END', '''''') + +# MAV_MODE +enums['MAV_MODE'] = {} +MAV_MODE_PREFLIGHT = 0 # System is not ready to fly, booting, calibrating, etc. No flag is set. +enums['MAV_MODE'][0] = EnumEntry('MAV_MODE_PREFLIGHT', '''System is not ready to fly, booting, calibrating, etc. No flag is set.''') +MAV_MODE_MANUAL_DISARMED = 64 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][64] = EnumEntry('MAV_MODE_MANUAL_DISARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_DISARMED = 66 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][66] = EnumEntry('MAV_MODE_TEST_DISARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_DISARMED = 80 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][80] = EnumEntry('MAV_MODE_STABILIZE_DISARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_DISARMED = 88 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][88] = EnumEntry('MAV_MODE_GUIDED_DISARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_DISARMED = 92 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][92] = EnumEntry('MAV_MODE_AUTO_DISARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_MANUAL_ARMED = 192 # System is allowed to be active, under manual (RC) control, no + # stabilization +enums['MAV_MODE'][192] = EnumEntry('MAV_MODE_MANUAL_ARMED', '''System is allowed to be active, under manual (RC) control, no stabilization''') +MAV_MODE_TEST_ARMED = 194 # UNDEFINED mode. This solely depends on the autopilot - use with + # caution, intended for developers only. +enums['MAV_MODE'][194] = EnumEntry('MAV_MODE_TEST_ARMED', '''UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.''') +MAV_MODE_STABILIZE_ARMED = 208 # System is allowed to be active, under assisted RC control. +enums['MAV_MODE'][208] = EnumEntry('MAV_MODE_STABILIZE_ARMED', '''System is allowed to be active, under assisted RC control.''') +MAV_MODE_GUIDED_ARMED = 216 # System is allowed to be active, under autonomous control, manual + # setpoint +enums['MAV_MODE'][216] = EnumEntry('MAV_MODE_GUIDED_ARMED', '''System is allowed to be active, under autonomous control, manual setpoint''') +MAV_MODE_AUTO_ARMED = 220 # System is allowed to be active, under autonomous control and + # navigation (the trajectory is decided + # onboard and not pre-programmed by MISSIONs) +enums['MAV_MODE'][220] = EnumEntry('MAV_MODE_AUTO_ARMED', '''System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)''') +MAV_MODE_ENUM_END = 221 # +enums['MAV_MODE'][221] = EnumEntry('MAV_MODE_ENUM_END', '''''') + +# MAV_STATE +enums['MAV_STATE'] = {} +MAV_STATE_UNINIT = 0 # Uninitialized system, state is unknown. +enums['MAV_STATE'][0] = EnumEntry('MAV_STATE_UNINIT', '''Uninitialized system, state is unknown.''') +MAV_STATE_BOOT = 1 # System is booting up. +enums['MAV_STATE'][1] = EnumEntry('MAV_STATE_BOOT', '''System is booting up.''') +MAV_STATE_CALIBRATING = 2 # System is calibrating and not flight-ready. +enums['MAV_STATE'][2] = EnumEntry('MAV_STATE_CALIBRATING', '''System is calibrating and not flight-ready.''') +MAV_STATE_STANDBY = 3 # System is grounded and on standby. It can be launched any time. +enums['MAV_STATE'][3] = EnumEntry('MAV_STATE_STANDBY', '''System is grounded and on standby. It can be launched any time.''') +MAV_STATE_ACTIVE = 4 # System is active and might be already airborne. Motors are engaged. +enums['MAV_STATE'][4] = EnumEntry('MAV_STATE_ACTIVE', '''System is active and might be already airborne. Motors are engaged.''') +MAV_STATE_CRITICAL = 5 # System is in a non-normal flight mode. It can however still navigate. +enums['MAV_STATE'][5] = EnumEntry('MAV_STATE_CRITICAL', '''System is in a non-normal flight mode. It can however still navigate.''') +MAV_STATE_EMERGENCY = 6 # System is in a non-normal flight mode. It lost control over parts or + # over the whole airframe. It is in mayday and + # going down. +enums['MAV_STATE'][6] = EnumEntry('MAV_STATE_EMERGENCY', '''System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.''') +MAV_STATE_POWEROFF = 7 # System just initialized its power-down sequence, will shut down now. +enums['MAV_STATE'][7] = EnumEntry('MAV_STATE_POWEROFF', '''System just initialized its power-down sequence, will shut down now.''') +MAV_STATE_ENUM_END = 8 # +enums['MAV_STATE'][8] = EnumEntry('MAV_STATE_ENUM_END', '''''') + +# MAV_COMPONENT +enums['MAV_COMPONENT'] = {} +MAV_COMP_ID_ALL = 0 # +enums['MAV_COMPONENT'][0] = EnumEntry('MAV_COMP_ID_ALL', '''''') +MAV_COMP_ID_CAMERA = 100 # +enums['MAV_COMPONENT'][100] = EnumEntry('MAV_COMP_ID_CAMERA', '''''') +MAV_COMP_ID_SERVO1 = 140 # +enums['MAV_COMPONENT'][140] = EnumEntry('MAV_COMP_ID_SERVO1', '''''') +MAV_COMP_ID_SERVO2 = 141 # +enums['MAV_COMPONENT'][141] = EnumEntry('MAV_COMP_ID_SERVO2', '''''') +MAV_COMP_ID_SERVO3 = 142 # +enums['MAV_COMPONENT'][142] = EnumEntry('MAV_COMP_ID_SERVO3', '''''') +MAV_COMP_ID_SERVO4 = 143 # +enums['MAV_COMPONENT'][143] = EnumEntry('MAV_COMP_ID_SERVO4', '''''') +MAV_COMP_ID_SERVO5 = 144 # +enums['MAV_COMPONENT'][144] = EnumEntry('MAV_COMP_ID_SERVO5', '''''') +MAV_COMP_ID_SERVO6 = 145 # +enums['MAV_COMPONENT'][145] = EnumEntry('MAV_COMP_ID_SERVO6', '''''') +MAV_COMP_ID_SERVO7 = 146 # +enums['MAV_COMPONENT'][146] = EnumEntry('MAV_COMP_ID_SERVO7', '''''') +MAV_COMP_ID_SERVO8 = 147 # +enums['MAV_COMPONENT'][147] = EnumEntry('MAV_COMP_ID_SERVO8', '''''') +MAV_COMP_ID_SERVO9 = 148 # +enums['MAV_COMPONENT'][148] = EnumEntry('MAV_COMP_ID_SERVO9', '''''') +MAV_COMP_ID_SERVO10 = 149 # +enums['MAV_COMPONENT'][149] = EnumEntry('MAV_COMP_ID_SERVO10', '''''') +MAV_COMP_ID_SERVO11 = 150 # +enums['MAV_COMPONENT'][150] = EnumEntry('MAV_COMP_ID_SERVO11', '''''') +MAV_COMP_ID_SERVO12 = 151 # +enums['MAV_COMPONENT'][151] = EnumEntry('MAV_COMP_ID_SERVO12', '''''') +MAV_COMP_ID_SERVO13 = 152 # +enums['MAV_COMPONENT'][152] = EnumEntry('MAV_COMP_ID_SERVO13', '''''') +MAV_COMP_ID_SERVO14 = 153 # +enums['MAV_COMPONENT'][153] = EnumEntry('MAV_COMP_ID_SERVO14', '''''') +MAV_COMP_ID_GIMBAL = 154 # +enums['MAV_COMPONENT'][154] = EnumEntry('MAV_COMP_ID_GIMBAL', '''''') +MAV_COMP_ID_LOG = 155 # +enums['MAV_COMPONENT'][155] = EnumEntry('MAV_COMP_ID_LOG', '''''') +MAV_COMP_ID_ADSB = 156 # +enums['MAV_COMPONENT'][156] = EnumEntry('MAV_COMP_ID_ADSB', '''''') +MAV_COMP_ID_OSD = 157 # On Screen Display (OSD) devices for video links +enums['MAV_COMPONENT'][157] = EnumEntry('MAV_COMP_ID_OSD', '''On Screen Display (OSD) devices for video links''') +MAV_COMP_ID_PERIPHERAL = 158 # Generic autopilot peripheral component ID. Meant for devices that do + # not implement the parameter sub-protocol +enums['MAV_COMPONENT'][158] = EnumEntry('MAV_COMP_ID_PERIPHERAL', '''Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol''') +MAV_COMP_ID_MAPPER = 180 # +enums['MAV_COMPONENT'][180] = EnumEntry('MAV_COMP_ID_MAPPER', '''''') +MAV_COMP_ID_MISSIONPLANNER = 190 # +enums['MAV_COMPONENT'][190] = EnumEntry('MAV_COMP_ID_MISSIONPLANNER', '''''') +MAV_COMP_ID_PATHPLANNER = 195 # +enums['MAV_COMPONENT'][195] = EnumEntry('MAV_COMP_ID_PATHPLANNER', '''''') +MAV_COMP_ID_IMU = 200 # +enums['MAV_COMPONENT'][200] = EnumEntry('MAV_COMP_ID_IMU', '''''') +MAV_COMP_ID_IMU_2 = 201 # +enums['MAV_COMPONENT'][201] = EnumEntry('MAV_COMP_ID_IMU_2', '''''') +MAV_COMP_ID_IMU_3 = 202 # +enums['MAV_COMPONENT'][202] = EnumEntry('MAV_COMP_ID_IMU_3', '''''') +MAV_COMP_ID_GPS = 220 # +enums['MAV_COMPONENT'][220] = EnumEntry('MAV_COMP_ID_GPS', '''''') +MAV_COMP_ID_UDP_BRIDGE = 240 # +enums['MAV_COMPONENT'][240] = EnumEntry('MAV_COMP_ID_UDP_BRIDGE', '''''') +MAV_COMP_ID_UART_BRIDGE = 241 # +enums['MAV_COMPONENT'][241] = EnumEntry('MAV_COMP_ID_UART_BRIDGE', '''''') +MAV_COMP_ID_SYSTEM_CONTROL = 250 # +enums['MAV_COMPONENT'][250] = EnumEntry('MAV_COMP_ID_SYSTEM_CONTROL', '''''') +MAV_COMPONENT_ENUM_END = 251 # +enums['MAV_COMPONENT'][251] = EnumEntry('MAV_COMPONENT_ENUM_END', '''''') + +# MAV_SYS_STATUS_SENSOR +enums['MAV_SYS_STATUS_SENSOR'] = {} +MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 # 0x01 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][1] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO', '''0x01 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 # 0x02 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][2] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL', '''0x02 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG = 4 # 0x04 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][4] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG', '''0x04 3D magnetometer''') +MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 # 0x08 absolute pressure +enums['MAV_SYS_STATUS_SENSOR'][8] = EnumEntry('MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE', '''0x08 absolute pressure''') +MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 # 0x10 differential pressure +enums['MAV_SYS_STATUS_SENSOR'][16] = EnumEntry('MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE', '''0x10 differential pressure''') +MAV_SYS_STATUS_SENSOR_GPS = 32 # 0x20 GPS +enums['MAV_SYS_STATUS_SENSOR'][32] = EnumEntry('MAV_SYS_STATUS_SENSOR_GPS', '''0x20 GPS''') +MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 # 0x40 optical flow +enums['MAV_SYS_STATUS_SENSOR'][64] = EnumEntry('MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW', '''0x40 optical flow''') +MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 # 0x80 computer vision position +enums['MAV_SYS_STATUS_SENSOR'][128] = EnumEntry('MAV_SYS_STATUS_SENSOR_VISION_POSITION', '''0x80 computer vision position''') +MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 # 0x100 laser based position +enums['MAV_SYS_STATUS_SENSOR'][256] = EnumEntry('MAV_SYS_STATUS_SENSOR_LASER_POSITION', '''0x100 laser based position''') +MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 # 0x200 external ground truth (Vicon or Leica) +enums['MAV_SYS_STATUS_SENSOR'][512] = EnumEntry('MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH', '''0x200 external ground truth (Vicon or Leica)''') +MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 # 0x400 3D angular rate control +enums['MAV_SYS_STATUS_SENSOR'][1024] = EnumEntry('MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL', '''0x400 3D angular rate control''') +MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 # 0x800 attitude stabilization +enums['MAV_SYS_STATUS_SENSOR'][2048] = EnumEntry('MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION', '''0x800 attitude stabilization''') +MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 # 0x1000 yaw position +enums['MAV_SYS_STATUS_SENSOR'][4096] = EnumEntry('MAV_SYS_STATUS_SENSOR_YAW_POSITION', '''0x1000 yaw position''') +MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 # 0x2000 z/altitude control +enums['MAV_SYS_STATUS_SENSOR'][8192] = EnumEntry('MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL', '''0x2000 z/altitude control''') +MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 # 0x4000 x/y position control +enums['MAV_SYS_STATUS_SENSOR'][16384] = EnumEntry('MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL', '''0x4000 x/y position control''') +MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 # 0x8000 motor outputs / control +enums['MAV_SYS_STATUS_SENSOR'][32768] = EnumEntry('MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS', '''0x8000 motor outputs / control''') +MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 # 0x10000 rc receiver +enums['MAV_SYS_STATUS_SENSOR'][65536] = EnumEntry('MAV_SYS_STATUS_SENSOR_RC_RECEIVER', '''0x10000 rc receiver''') +MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 # 0x20000 2nd 3D gyro +enums['MAV_SYS_STATUS_SENSOR'][131072] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_GYRO2', '''0x20000 2nd 3D gyro''') +MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 # 0x40000 2nd 3D accelerometer +enums['MAV_SYS_STATUS_SENSOR'][262144] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_ACCEL2', '''0x40000 2nd 3D accelerometer''') +MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 # 0x80000 2nd 3D magnetometer +enums['MAV_SYS_STATUS_SENSOR'][524288] = EnumEntry('MAV_SYS_STATUS_SENSOR_3D_MAG2', '''0x80000 2nd 3D magnetometer''') +MAV_SYS_STATUS_GEOFENCE = 1048576 # 0x100000 geofence +enums['MAV_SYS_STATUS_SENSOR'][1048576] = EnumEntry('MAV_SYS_STATUS_GEOFENCE', '''0x100000 geofence''') +MAV_SYS_STATUS_AHRS = 2097152 # 0x200000 AHRS subsystem health +enums['MAV_SYS_STATUS_SENSOR'][2097152] = EnumEntry('MAV_SYS_STATUS_AHRS', '''0x200000 AHRS subsystem health''') +MAV_SYS_STATUS_TERRAIN = 4194304 # 0x400000 Terrain subsystem health +enums['MAV_SYS_STATUS_SENSOR'][4194304] = EnumEntry('MAV_SYS_STATUS_TERRAIN', '''0x400000 Terrain subsystem health''') +MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 # 0x800000 Motors are reversed +enums['MAV_SYS_STATUS_SENSOR'][8388608] = EnumEntry('MAV_SYS_STATUS_REVERSE_MOTOR', '''0x800000 Motors are reversed''') +MAV_SYS_STATUS_SENSOR_ENUM_END = 8388609 # +enums['MAV_SYS_STATUS_SENSOR'][8388609] = EnumEntry('MAV_SYS_STATUS_SENSOR_ENUM_END', '''''') + +# MAV_FRAME +enums['MAV_FRAME'] = {} +MAV_FRAME_GLOBAL = 0 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude, second value / y: longitude, third + # value / z: positive altitude over mean sea + # level (MSL) +enums['MAV_FRAME'][0] = EnumEntry('MAV_FRAME_GLOBAL', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_LOCAL_NED = 1 # Local coordinate frame, Z-up (x: north, y: east, z: down). +enums['MAV_FRAME'][1] = EnumEntry('MAV_FRAME_LOCAL_NED', '''Local coordinate frame, Z-up (x: north, y: east, z: down).''') +MAV_FRAME_MISSION = 2 # NOT a coordinate frame, indicates a mission command. +enums['MAV_FRAME'][2] = EnumEntry('MAV_FRAME_MISSION', '''NOT a coordinate frame, indicates a mission command.''') +MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude, second + # value / y: longitude, third value / z: + # positive altitude with 0 being at the + # altitude of the home location. +enums['MAV_FRAME'][3] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_ENU = 4 # Local coordinate frame, Z-down (x: east, y: north, z: up) +enums['MAV_FRAME'][4] = EnumEntry('MAV_FRAME_LOCAL_ENU', '''Local coordinate frame, Z-down (x: east, y: north, z: up)''') +MAV_FRAME_GLOBAL_INT = 5 # Global coordinate frame, WGS84 coordinate system. First value / x: + # latitude in degrees*1.0e-7, second value / + # y: longitude in degrees*1.0e-7, third value + # / z: positive altitude over mean sea level + # (MSL) +enums['MAV_FRAME'][5] = EnumEntry('MAV_FRAME_GLOBAL_INT', '''Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)''') +MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6 # Global coordinate frame, WGS84 coordinate system, relative altitude + # over ground with respect to the home + # position. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude with 0 being at the altitude of the + # home location. +enums['MAV_FRAME'][6] = EnumEntry('MAV_FRAME_GLOBAL_RELATIVE_ALT_INT', '''Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.''') +MAV_FRAME_LOCAL_OFFSET_NED = 7 # Offset to the current local frame. Anything expressed in this frame + # should be added to the current local frame + # position. +enums['MAV_FRAME'][7] = EnumEntry('MAV_FRAME_LOCAL_OFFSET_NED', '''Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.''') +MAV_FRAME_BODY_NED = 8 # Setpoint in body NED frame. This makes sense if all position control + # is externalized - e.g. useful to command 2 + # m/s^2 acceleration to the right. +enums['MAV_FRAME'][8] = EnumEntry('MAV_FRAME_BODY_NED', '''Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.''') +MAV_FRAME_BODY_OFFSET_NED = 9 # Offset in body NED frame. This makes sense if adding setpoints to the + # current flight path, to avoid an obstacle - + # e.g. useful to command 2 m/s^2 acceleration + # to the east. +enums['MAV_FRAME'][9] = EnumEntry('MAV_FRAME_BODY_OFFSET_NED', '''Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees, second value / y: longitude in + # degrees, third value / z: positive altitude + # in meters with 0 being at ground level in + # terrain model. +enums['MAV_FRAME'][10] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 # Global coordinate frame with above terrain level altitude. WGS84 + # coordinate system, relative altitude over + # terrain with respect to the waypoint + # coordinate. First value / x: latitude in + # degrees*10e-7, second value / y: longitude + # in degrees*10e-7, third value / z: positive + # altitude in meters with 0 being at ground + # level in terrain model. +enums['MAV_FRAME'][11] = EnumEntry('MAV_FRAME_GLOBAL_TERRAIN_ALT_INT', '''Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.''') +MAV_FRAME_ENUM_END = 12 # +enums['MAV_FRAME'][12] = EnumEntry('MAV_FRAME_ENUM_END', '''''') + +# MAVLINK_DATA_STREAM_TYPE +enums['MAVLINK_DATA_STREAM_TYPE'] = {} +MAVLINK_DATA_STREAM_IMG_JPEG = 1 # +enums['MAVLINK_DATA_STREAM_TYPE'][1] = EnumEntry('MAVLINK_DATA_STREAM_IMG_JPEG', '''''') +MAVLINK_DATA_STREAM_IMG_BMP = 2 # +enums['MAVLINK_DATA_STREAM_TYPE'][2] = EnumEntry('MAVLINK_DATA_STREAM_IMG_BMP', '''''') +MAVLINK_DATA_STREAM_IMG_RAW8U = 3 # +enums['MAVLINK_DATA_STREAM_TYPE'][3] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW8U', '''''') +MAVLINK_DATA_STREAM_IMG_RAW32U = 4 # +enums['MAVLINK_DATA_STREAM_TYPE'][4] = EnumEntry('MAVLINK_DATA_STREAM_IMG_RAW32U', '''''') +MAVLINK_DATA_STREAM_IMG_PGM = 5 # +enums['MAVLINK_DATA_STREAM_TYPE'][5] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PGM', '''''') +MAVLINK_DATA_STREAM_IMG_PNG = 6 # +enums['MAVLINK_DATA_STREAM_TYPE'][6] = EnumEntry('MAVLINK_DATA_STREAM_IMG_PNG', '''''') +MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7 # +enums['MAVLINK_DATA_STREAM_TYPE'][7] = EnumEntry('MAVLINK_DATA_STREAM_TYPE_ENUM_END', '''''') + +# FENCE_ACTION +enums['FENCE_ACTION'] = {} +FENCE_ACTION_NONE = 0 # Disable fenced mode +enums['FENCE_ACTION'][0] = EnumEntry('FENCE_ACTION_NONE', '''Disable fenced mode''') +FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0) +enums['FENCE_ACTION'][1] = EnumEntry('FENCE_ACTION_GUIDED', '''Switched to guided mode to return point (fence point 0)''') +FENCE_ACTION_REPORT = 2 # Report fence breach, but don't take action +enums['FENCE_ACTION'][2] = EnumEntry('FENCE_ACTION_REPORT', '''Report fence breach, but don't take action''') +FENCE_ACTION_GUIDED_THR_PASS = 3 # Switched to guided mode to return point (fence point 0) with manual + # throttle control +enums['FENCE_ACTION'][3] = EnumEntry('FENCE_ACTION_GUIDED_THR_PASS', '''Switched to guided mode to return point (fence point 0) with manual throttle control''') +FENCE_ACTION_ENUM_END = 4 # +enums['FENCE_ACTION'][4] = EnumEntry('FENCE_ACTION_ENUM_END', '''''') + +# FENCE_BREACH +enums['FENCE_BREACH'] = {} +FENCE_BREACH_NONE = 0 # No last fence breach +enums['FENCE_BREACH'][0] = EnumEntry('FENCE_BREACH_NONE', '''No last fence breach''') +FENCE_BREACH_MINALT = 1 # Breached minimum altitude +enums['FENCE_BREACH'][1] = EnumEntry('FENCE_BREACH_MINALT', '''Breached minimum altitude''') +FENCE_BREACH_MAXALT = 2 # Breached maximum altitude +enums['FENCE_BREACH'][2] = EnumEntry('FENCE_BREACH_MAXALT', '''Breached maximum altitude''') +FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary +enums['FENCE_BREACH'][3] = EnumEntry('FENCE_BREACH_BOUNDARY', '''Breached fence boundary''') +FENCE_BREACH_ENUM_END = 4 # +enums['FENCE_BREACH'][4] = EnumEntry('FENCE_BREACH_ENUM_END', '''''') + +# MAV_MOUNT_MODE +enums['MAV_MOUNT_MODE'] = {} +MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permant memory and + # stop stabilization +enums['MAV_MOUNT_MODE'][0] = EnumEntry('MAV_MOUNT_MODE_RETRACT', '''Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization''') +MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. +enums['MAV_MOUNT_MODE'][1] = EnumEntry('MAV_MOUNT_MODE_NEUTRAL', '''Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.''') +MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][2] = EnumEntry('MAV_MOUNT_MODE_MAVLINK_TARGETING', '''Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with + # stabilization +enums['MAV_MOUNT_MODE'][3] = EnumEntry('MAV_MOUNT_MODE_RC_TARGETING', '''Load neutral position and start RC Roll,Pitch,Yaw control with stabilization''') +MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt +enums['MAV_MOUNT_MODE'][4] = EnumEntry('MAV_MOUNT_MODE_GPS_POINT', '''Load neutral position and start to point to Lat,Lon,Alt''') +MAV_MOUNT_MODE_ENUM_END = 5 # +enums['MAV_MOUNT_MODE'][5] = EnumEntry('MAV_MOUNT_MODE_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_CPU_LOAD = 170 +MAVLINK_MSG_ID_SENSOR_BIAS = 172 +MAVLINK_MSG_ID_DIAGNOSTIC = 173 +MAVLINK_MSG_ID_SLUGS_NAVIGATION = 176 +MAVLINK_MSG_ID_DATA_LOG = 177 +MAVLINK_MSG_ID_GPS_DATE_TIME = 179 +MAVLINK_MSG_ID_MID_LVL_CMDS = 180 +MAVLINK_MSG_ID_CTRL_SRFC_PT = 181 +MAVLINK_MSG_ID_SLUGS_CAMERA_ORDER = 184 +MAVLINK_MSG_ID_CONTROL_SURFACE = 185 +MAVLINK_MSG_ID_SLUGS_MOBILE_LOCATION = 186 +MAVLINK_MSG_ID_SLUGS_CONFIGURATION_CAMERA = 188 +MAVLINK_MSG_ID_ISR_LOCATION = 189 +MAVLINK_MSG_ID_VOLT_SENSOR = 191 +MAVLINK_MSG_ID_PTZ_STATUS = 192 +MAVLINK_MSG_ID_UAV_STATUS = 193 +MAVLINK_MSG_ID_STATUS_GPS = 194 +MAVLINK_MSG_ID_NOVATEL_DIAG = 195 +MAVLINK_MSG_ID_SENSOR_DIAG = 196 +MAVLINK_MSG_ID_BOOT = 197 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_cpu_load_message(MAVLink_message): + ''' + Sensor and DSC control loads. + ''' + id = MAVLINK_MSG_ID_CPU_LOAD + name = 'CPU_LOAD' + fieldnames = ['sensLoad', 'ctrlLoad', 'batVolt'] + ordered_fieldnames = [ 'batVolt', 'sensLoad', 'ctrlLoad' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/slugs.xml b/pymavlink/dialects/v10/slugs.xml new file mode 100755 index 0000000..a985eab --- /dev/null +++ b/pymavlink/dialects/v10/slugs.xml @@ -0,0 +1,339 @@ + + + common.xml + + + + + + Does nothing. + 1 to arm, 0 to disarm + + + + + + Return vehicle to base. + 0: return to base, 1: track mobile base + + + Stops the vehicle from returning to base and resumes flight. + + + Turns the vehicle's visible or infrared lights on or off. + 0: visible lights, 1: infrared lights + 0: turn on, 1: turn off + + + Requests vehicle to send current mid-level commands to ground station. + + + Requests storage of mid-level commands. + Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM + + + + + + Slugs-specific navigation modes. + + No change to SLUGS mode. + + + Vehicle is in liftoff mode. + + + Vehicle is in passthrough mode, being controlled by a pilot. + + + Vehicle is in waypoint mode, navigating to waypoints. + + + Vehicle is executing mid-level commands. + + + Vehicle is returning to the home location. + + + Vehicle is landing. + + + Lost connection with vehicle. + + + Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. + + + Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. + + + Vehicle is patrolling along lines between waypoints. + + + Vehicle is grounded or an error has occurred. + + + + + These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console + has control of the surface, and if not then the autopilot has control of the surface. + + 0b10000000 Throttle control passes through to pilot console. + + + 0b01000000 Left aileron control passes through to pilot console. + + + 0b00100000 Right aileron control passes through to pilot console. + + + 0b00010000 Rudder control passes through to pilot console. + + + 0b00001000 Left elevator control passes through to pilot console. + + + 0b00000100 Right elevator control passes through to pilot console. + + + 0b00000010 Left flap control passes through to pilot console. + + + 0b00000001 Right flap control passes through to pilot console. + + + + + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the nav filter in m/s + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + Commanded altitude in 0.1 m + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Clock Status. See table 47 page 211 OEMStar Manual + Visible satellites reported by Gps + Used satellites in Solution + GPS+GLONASS satellites in Solution + GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) + Percent used GPS + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground. + The system setting the commands + Commanded Altitude in meters + Commanded Airspeed in m/s + Commanded Turnrate in rad/s + + + + This message sets the control surfaces for selective passthrough mode. + The system setting the commands + Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. + + + + Orders generated to the SLUGS camera mount. + The system reporting the action + Order the mount to pan: -1 left, 0 No pan motion, +1 right + Order the mount to tilt: -1 down, 0 No tilt motion, +1 up + Order the zoom values 0 to 10 + Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored + + + + Control for surface; pending and order to origin. + The system setting the commands + ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder + Pending + Order to origin + + + + + + + Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled + The system reporting the action + Mobile Latitude + Mobile Longitude + + + + Control for camara. + The system setting the commands + ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight + 1: up/on 2: down/off 3: auto/reset/no action + + + + Transmits the position of watch + The system reporting the action + ISR Latitude + ISR Longitude + ISR Height + Option 1 + Option 2 + Option 3 + + + + + + + Transmits the readings from the voltage and current sensors + It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM + Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V + Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value + + + + Transmits the actual Pan, Tilt and Zoom values of the camera unit + The actual Zoom Value + The Pan value in 10ths of degree + The Tilt value in 10ths of degree + + + + Transmits the actual status values UAV in flight + The ID system reporting the action + Latitude UAV + Longitude UAV + Altitude UAV + Speed UAV + Course UAV + + + + This contains the status of the GPS readings + Number of times checksum has failed + The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a + Indicates if GN, GL or GP messages are being received + A = data valid, V = data invalid + Magnetic variation, degrees + Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course + Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid + + + + Transmits the diagnostics data from the Novatel OEMStar GPS + The Time Status. See Table 8 page 27 Novatel OEMStar Manual + Status Bitfield. See table 69 page 350 Novatel OEMstar Manual + solution Status. See table 44 page 197 + position type. See table 43 page 196 + velocity type. See table 43 page 196 + Age of the position solution in seconds + Times the CRC has failed since boot + + + + Diagnostic data Sensor MCU + Float field 1 + Float field 2 + Int 16 field 1 + Int 8 field 1 + + + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup. + The onboard software version + + + diff --git a/pymavlink/dialects/v10/test.py b/pymavlink/dialects/v10/test.py new file mode 100644 index 0000000..51c2953 --- /dev/null +++ b/pymavlink/dialects/v10/test.py @@ -0,0 +1,536 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: test.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "test" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack('= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/pymavlink/dialects/v10/ualberta.py b/pymavlink/dialects/v10/ualberta.py new file mode 100644 index 0000000..1a48242 --- /dev/null +++ b/pymavlink/dialects/v10/ualberta.py @@ -0,0 +1,11150 @@ +''' +MAVLink protocol implementation (auto-generated by mavgen.py) + +Generated from: ualberta.xml,common.xml + +Note: this file has been auto-generated. DO NOT EDIT +''' + +import struct, array, time, json, os, sys, platform + +from ...generator.mavcrc import x25crc + +WIRE_PROTOCOL_VERSION = "1.0" +DIALECT = "ualberta" + +native_supported = platform.system() != 'Windows' # Not yet supported on other dialects +native_force = 'MAVNATIVE_FORCE' in os.environ # Will force use of native code regardless of what client app wants +native_testing = 'MAVNATIVE_TESTING' in os.environ # Will force both native and legacy code to be used and their results compared + +if native_supported: + try: + import mavnative + except ImportError: + print("ERROR LOADING MAVNATIVE - falling back to python implementation") + native_supported = False + +# some base types from mavlink_types.h +MAVLINK_TYPE_CHAR = 0 +MAVLINK_TYPE_UINT8_T = 1 +MAVLINK_TYPE_INT8_T = 2 +MAVLINK_TYPE_UINT16_T = 3 +MAVLINK_TYPE_INT16_T = 4 +MAVLINK_TYPE_UINT32_T = 5 +MAVLINK_TYPE_INT32_T = 6 +MAVLINK_TYPE_UINT64_T = 7 +MAVLINK_TYPE_INT64_T = 8 +MAVLINK_TYPE_FLOAT = 9 +MAVLINK_TYPE_DOUBLE = 10 + + +class MAVLink_header(object): + '''MAVLink message header''' + def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): + self.mlen = mlen + self.seq = seq + self.srcSystem = srcSystem + self.srcComponent = srcComponent + self.msgId = msgId + + def pack(self): + return struct.pack('BBBBBB', 254, self.mlen, self.seq, + self.srcSystem, self.srcComponent, self.msgId) + +class MAVLink_message(object): + '''base MAVLink message class''' + def __init__(self, msgId, name): + self._header = MAVLink_header(msgId) + self._payload = None + self._msgbuf = None + self._crc = None + self._fieldnames = [] + self._type = name + + def get_msgbuf(self): + if isinstance(self._msgbuf, bytearray): + return self._msgbuf + return bytearray(self._msgbuf) + + def get_header(self): + return self._header + + def get_payload(self): + return self._payload + + def get_crc(self): + return self._crc + + def get_fieldnames(self): + return self._fieldnames + + def get_type(self): + return self._type + + def get_msgId(self): + return self._header.msgId + + def get_srcSystem(self): + return self._header.srcSystem + + def get_srcComponent(self): + return self._header.srcComponent + + def get_seq(self): + return self._header.seq + + def __str__(self): + ret = '%s {' % self._type + for a in self._fieldnames: + v = getattr(self, a) + ret += '%s : %s, ' % (a, v) + ret = ret[0:-2] + '}' + return ret + + def __ne__(self, other): + return not self.__eq__(other) + + def __eq__(self, other): + if other == None: + return False + + if self.get_type() != other.get_type(): + return False + + # We do not compare CRC because native code doesn't provide it + #if self.get_crc() != other.get_crc(): + # return False + + if self.get_seq() != other.get_seq(): + return False + + if self.get_srcSystem() != other.get_srcSystem(): + return False + + if self.get_srcComponent() != other.get_srcComponent(): + return False + + for a in self._fieldnames: + if getattr(self, a) != getattr(other, a): + return False + + return True + + def to_dict(self): + d = dict({}) + d['mavpackettype'] = self._type + for a in self._fieldnames: + d[a] = getattr(self, a) + return d + + def to_json(self): + return json.dumps(self.to_dict()) + + def pack(self, mav, crc_extra, payload): + self._payload = payload + self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, + mav.srcSystem, mav.srcComponent) + self._msgbuf = self._header.pack() + payload + crc = x25crc(self._msgbuf[1:]) + if True: # using CRC extra + crc.accumulate_str(struct.pack('B', crc_extra)) + self._crc = crc.crc + self._msgbuf += struct.pack(' 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.''' +enums['MAV_CMD'][16].param[4] = '''Desired yaw angle at MISSION (rotary wing)''' +enums['MAV_CMD'][16].param[5] = '''Latitude''' +enums['MAV_CMD'][16].param[6] = '''Longitude''' +enums['MAV_CMD'][16].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this MISSION an unlimited amount of time +enums['MAV_CMD'][17] = EnumEntry('MAV_CMD_NAV_LOITER_UNLIM', '''Loiter around this MISSION an unlimited amount of time''') +enums['MAV_CMD'][17].param[1] = '''Empty''' +enums['MAV_CMD'][17].param[2] = '''Empty''' +enums['MAV_CMD'][17].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][17].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][17].param[5] = '''Latitude''' +enums['MAV_CMD'][17].param[6] = '''Longitude''' +enums['MAV_CMD'][17].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this MISSION for X turns +enums['MAV_CMD'][18] = EnumEntry('MAV_CMD_NAV_LOITER_TURNS', '''Loiter around this MISSION for X turns''') +enums['MAV_CMD'][18].param[1] = '''Turns''' +enums['MAV_CMD'][18].param[2] = '''Empty''' +enums['MAV_CMD'][18].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][18].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][18].param[5] = '''Latitude''' +enums['MAV_CMD'][18].param[6] = '''Longitude''' +enums['MAV_CMD'][18].param[7] = '''Altitude''' +MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this MISSION for X seconds +enums['MAV_CMD'][19] = EnumEntry('MAV_CMD_NAV_LOITER_TIME', '''Loiter around this MISSION for X seconds''') +enums['MAV_CMD'][19].param[1] = '''Seconds (decimal)''' +enums['MAV_CMD'][19].param[2] = '''Empty''' +enums['MAV_CMD'][19].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][19].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][19].param[5] = '''Latitude''' +enums['MAV_CMD'][19].param[6] = '''Longitude''' +enums['MAV_CMD'][19].param[7] = '''Altitude''' +MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location +enums['MAV_CMD'][20] = EnumEntry('MAV_CMD_NAV_RETURN_TO_LAUNCH', '''Return to launch location''') +enums['MAV_CMD'][20].param[1] = '''Empty''' +enums['MAV_CMD'][20].param[2] = '''Empty''' +enums['MAV_CMD'][20].param[3] = '''Empty''' +enums['MAV_CMD'][20].param[4] = '''Empty''' +enums['MAV_CMD'][20].param[5] = '''Empty''' +enums['MAV_CMD'][20].param[6] = '''Empty''' +enums['MAV_CMD'][20].param[7] = '''Empty''' +MAV_CMD_NAV_LAND = 21 # Land at location +enums['MAV_CMD'][21] = EnumEntry('MAV_CMD_NAV_LAND', '''Land at location''') +enums['MAV_CMD'][21].param[1] = '''Abort Alt''' +enums['MAV_CMD'][21].param[2] = '''Empty''' +enums['MAV_CMD'][21].param[3] = '''Empty''' +enums['MAV_CMD'][21].param[4] = '''Desired yaw angle''' +enums['MAV_CMD'][21].param[5] = '''Latitude''' +enums['MAV_CMD'][21].param[6] = '''Longitude''' +enums['MAV_CMD'][21].param[7] = '''Altitude''' +MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand +enums['MAV_CMD'][22] = EnumEntry('MAV_CMD_NAV_TAKEOFF', '''Takeoff from ground / hand''') +enums['MAV_CMD'][22].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor''' +enums['MAV_CMD'][22].param[2] = '''Empty''' +enums['MAV_CMD'][22].param[3] = '''Empty''' +enums['MAV_CMD'][22].param[4] = '''Yaw angle (if magnetometer present), ignored without magnetometer''' +enums['MAV_CMD'][22].param[5] = '''Latitude''' +enums['MAV_CMD'][22].param[6] = '''Longitude''' +enums['MAV_CMD'][22].param[7] = '''Altitude''' +MAV_CMD_NAV_LAND_LOCAL = 23 # Land at local position (local frame only) +enums['MAV_CMD'][23] = EnumEntry('MAV_CMD_NAV_LAND_LOCAL', '''Land at local position (local frame only)''') +enums['MAV_CMD'][23].param[1] = '''Landing target number (if available)''' +enums['MAV_CMD'][23].param[2] = '''Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land''' +enums['MAV_CMD'][23].param[3] = '''Landing descend rate [ms^-1]''' +enums['MAV_CMD'][23].param[4] = '''Desired yaw angle [rad]''' +enums['MAV_CMD'][23].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][23].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][23].param[7] = '''Z-axis / ground level position [m]''' +MAV_CMD_NAV_TAKEOFF_LOCAL = 24 # Takeoff from local position (local frame only) +enums['MAV_CMD'][24] = EnumEntry('MAV_CMD_NAV_TAKEOFF_LOCAL', '''Takeoff from local position (local frame only)''') +enums['MAV_CMD'][24].param[1] = '''Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]''' +enums['MAV_CMD'][24].param[2] = '''Empty''' +enums['MAV_CMD'][24].param[3] = '''Takeoff ascend rate [ms^-1]''' +enums['MAV_CMD'][24].param[4] = '''Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these''' +enums['MAV_CMD'][24].param[5] = '''Y-axis position [m]''' +enums['MAV_CMD'][24].param[6] = '''X-axis position [m]''' +enums['MAV_CMD'][24].param[7] = '''Z-axis position [m]''' +MAV_CMD_NAV_FOLLOW = 25 # Vehicle following, i.e. this waypoint represents the position of a + # moving vehicle +enums['MAV_CMD'][25] = EnumEntry('MAV_CMD_NAV_FOLLOW', '''Vehicle following, i.e. this waypoint represents the position of a moving vehicle''') +enums['MAV_CMD'][25].param[1] = '''Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation''' +enums['MAV_CMD'][25].param[2] = '''Ground speed of vehicle to be followed''' +enums['MAV_CMD'][25].param[3] = '''Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise''' +enums['MAV_CMD'][25].param[4] = '''Desired yaw angle.''' +enums['MAV_CMD'][25].param[5] = '''Latitude''' +enums['MAV_CMD'][25].param[6] = '''Longitude''' +enums['MAV_CMD'][25].param[7] = '''Altitude''' +MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30 # Continue on the current course and climb/descend to specified + # altitude. When the altitude is reached + # continue to the next command (i.e., don't + # proceed to the next command until the + # desired altitude is reached. +enums['MAV_CMD'][30] = EnumEntry('MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT', '''Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.''') +enums['MAV_CMD'][30].param[1] = '''Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. ''' +enums['MAV_CMD'][30].param[2] = '''Empty''' +enums['MAV_CMD'][30].param[3] = '''Empty''' +enums['MAV_CMD'][30].param[4] = '''Empty''' +enums['MAV_CMD'][30].param[5] = '''Empty''' +enums['MAV_CMD'][30].param[6] = '''Empty''' +enums['MAV_CMD'][30].param[7] = '''Desired altitude in meters''' +MAV_CMD_NAV_LOITER_TO_ALT = 31 # Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, + # then loiter at the current position. Don't + # consider the navigation command complete + # (don't leave loiter) until the altitude has + # been reached. Additionally, if the Heading + # Required parameter is non-zero the aircraft + # will not leave the loiter until heading + # toward the next waypoint. +enums['MAV_CMD'][31] = EnumEntry('MAV_CMD_NAV_LOITER_TO_ALT', '''Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. ''') +enums['MAV_CMD'][31].param[1] = '''Heading Required (0 = False)''' +enums['MAV_CMD'][31].param[2] = '''Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.''' +enums['MAV_CMD'][31].param[3] = '''Empty''' +enums['MAV_CMD'][31].param[4] = '''Empty''' +enums['MAV_CMD'][31].param[5] = '''Latitude''' +enums['MAV_CMD'][31].param[6] = '''Longitude''' +enums['MAV_CMD'][31].param[7] = '''Altitude''' +MAV_CMD_DO_FOLLOW = 32 # Being following a target +enums['MAV_CMD'][32] = EnumEntry('MAV_CMD_DO_FOLLOW', '''Being following a target''') +enums['MAV_CMD'][32].param[1] = '''System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode''' +enums['MAV_CMD'][32].param[2] = '''RESERVED''' +enums['MAV_CMD'][32].param[3] = '''RESERVED''' +enums['MAV_CMD'][32].param[4] = '''altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home''' +enums['MAV_CMD'][32].param[5] = '''altitude''' +enums['MAV_CMD'][32].param[6] = '''RESERVED''' +enums['MAV_CMD'][32].param[7] = '''TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout''' +MAV_CMD_DO_FOLLOW_REPOSITION = 33 # Reposition the MAV after a follow target command has been sent +enums['MAV_CMD'][33] = EnumEntry('MAV_CMD_DO_FOLLOW_REPOSITION', '''Reposition the MAV after a follow target command has been sent''') +enums['MAV_CMD'][33].param[1] = '''Camera q1 (where 0 is on the ray from the camera to the tracking device)''' +enums['MAV_CMD'][33].param[2] = '''Camera q2''' +enums['MAV_CMD'][33].param[3] = '''Camera q3''' +enums['MAV_CMD'][33].param[4] = '''Camera q4''' +enums['MAV_CMD'][33].param[5] = '''altitude offset from target (m)''' +enums['MAV_CMD'][33].param[6] = '''X offset from target (m)''' +enums['MAV_CMD'][33].param[7] = '''Y offset from target (m)''' +MAV_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][80] = EnumEntry('MAV_CMD_NAV_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][80].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][80].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][80].param[4] = '''Empty''' +enums['MAV_CMD'][80].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][80].param[6] = '''y''' +enums['MAV_CMD'][80].param[7] = '''z''' +MAV_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. +enums['MAV_CMD'][81] = EnumEntry('MAV_CMD_NAV_PATHPLANNING', '''Control autonomous path planning on the MAV.''') +enums['MAV_CMD'][81].param[1] = '''0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning''' +enums['MAV_CMD'][81].param[2] = '''0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid''' +enums['MAV_CMD'][81].param[3] = '''Empty''' +enums['MAV_CMD'][81].param[4] = '''Yaw angle at goal, in compass degrees, [0..360]''' +enums['MAV_CMD'][81].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][81].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][81].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_SPLINE_WAYPOINT = 82 # Navigate to MISSION using a spline path. +enums['MAV_CMD'][82] = EnumEntry('MAV_CMD_NAV_SPLINE_WAYPOINT', '''Navigate to MISSION using a spline path.''') +enums['MAV_CMD'][82].param[1] = '''Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)''' +enums['MAV_CMD'][82].param[2] = '''Empty''' +enums['MAV_CMD'][82].param[3] = '''Empty''' +enums['MAV_CMD'][82].param[4] = '''Empty''' +enums['MAV_CMD'][82].param[5] = '''Latitude/X of goal''' +enums['MAV_CMD'][82].param[6] = '''Longitude/Y of goal''' +enums['MAV_CMD'][82].param[7] = '''Altitude/Z of goal''' +MAV_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground using VTOL mode +enums['MAV_CMD'][84] = EnumEntry('MAV_CMD_NAV_VTOL_TAKEOFF', '''Takeoff from ground using VTOL mode''') +enums['MAV_CMD'][84].param[1] = '''Empty''' +enums['MAV_CMD'][84].param[2] = '''Empty''' +enums['MAV_CMD'][84].param[3] = '''Empty''' +enums['MAV_CMD'][84].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][84].param[5] = '''Latitude''' +enums['MAV_CMD'][84].param[6] = '''Longitude''' +enums['MAV_CMD'][84].param[7] = '''Altitude''' +MAV_CMD_NAV_VTOL_LAND = 85 # Land using VTOL mode +enums['MAV_CMD'][85] = EnumEntry('MAV_CMD_NAV_VTOL_LAND', '''Land using VTOL mode''') +enums['MAV_CMD'][85].param[1] = '''Empty''' +enums['MAV_CMD'][85].param[2] = '''Empty''' +enums['MAV_CMD'][85].param[3] = '''Empty''' +enums['MAV_CMD'][85].param[4] = '''Yaw angle in degrees''' +enums['MAV_CMD'][85].param[5] = '''Latitude''' +enums['MAV_CMD'][85].param[6] = '''Longitude''' +enums['MAV_CMD'][85].param[7] = '''Altitude''' +MAV_CMD_NAV_GUIDED_ENABLE = 92 # hand control over to an external controller +enums['MAV_CMD'][92] = EnumEntry('MAV_CMD_NAV_GUIDED_ENABLE', '''hand control over to an external controller''') +enums['MAV_CMD'][92].param[1] = '''On / Off (> 0.5f on)''' +enums['MAV_CMD'][92].param[2] = '''Empty''' +enums['MAV_CMD'][92].param[3] = '''Empty''' +enums['MAV_CMD'][92].param[4] = '''Empty''' +enums['MAV_CMD'][92].param[5] = '''Empty''' +enums['MAV_CMD'][92].param[6] = '''Empty''' +enums['MAV_CMD'][92].param[7] = '''Empty''' +MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the + # NAV/ACTION commands in the enumeration +enums['MAV_CMD'][95] = EnumEntry('MAV_CMD_NAV_LAST', '''NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration''') +enums['MAV_CMD'][95].param[1] = '''Empty''' +enums['MAV_CMD'][95].param[2] = '''Empty''' +enums['MAV_CMD'][95].param[3] = '''Empty''' +enums['MAV_CMD'][95].param[4] = '''Empty''' +enums['MAV_CMD'][95].param[5] = '''Empty''' +enums['MAV_CMD'][95].param[6] = '''Empty''' +enums['MAV_CMD'][95].param[7] = '''Empty''' +MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine. +enums['MAV_CMD'][112] = EnumEntry('MAV_CMD_CONDITION_DELAY', '''Delay mission state machine.''') +enums['MAV_CMD'][112].param[1] = '''Delay in seconds (decimal)''' +enums['MAV_CMD'][112].param[2] = '''Empty''' +enums['MAV_CMD'][112].param[3] = '''Empty''' +enums['MAV_CMD'][112].param[4] = '''Empty''' +enums['MAV_CMD'][112].param[5] = '''Empty''' +enums['MAV_CMD'][112].param[6] = '''Empty''' +enums['MAV_CMD'][112].param[7] = '''Empty''' +MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired + # altitude reached. +enums['MAV_CMD'][113] = EnumEntry('MAV_CMD_CONDITION_CHANGE_ALT', '''Ascend/descend at rate. Delay mission state machine until desired altitude reached.''') +enums['MAV_CMD'][113].param[1] = '''Descent / Ascend rate (m/s)''' +enums['MAV_CMD'][113].param[2] = '''Empty''' +enums['MAV_CMD'][113].param[3] = '''Empty''' +enums['MAV_CMD'][113].param[4] = '''Empty''' +enums['MAV_CMD'][113].param[5] = '''Empty''' +enums['MAV_CMD'][113].param[6] = '''Empty''' +enums['MAV_CMD'][113].param[7] = '''Finish Altitude''' +MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV + # point. +enums['MAV_CMD'][114] = EnumEntry('MAV_CMD_CONDITION_DISTANCE', '''Delay mission state machine until within desired distance of next NAV point.''') +enums['MAV_CMD'][114].param[1] = '''Distance (meters)''' +enums['MAV_CMD'][114].param[2] = '''Empty''' +enums['MAV_CMD'][114].param[3] = '''Empty''' +enums['MAV_CMD'][114].param[4] = '''Empty''' +enums['MAV_CMD'][114].param[5] = '''Empty''' +enums['MAV_CMD'][114].param[6] = '''Empty''' +enums['MAV_CMD'][114].param[7] = '''Empty''' +MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle. +enums['MAV_CMD'][115] = EnumEntry('MAV_CMD_CONDITION_YAW', '''Reach a certain target angle.''') +enums['MAV_CMD'][115].param[1] = '''target angle: [0-360], 0 is north''' +enums['MAV_CMD'][115].param[2] = '''speed during yaw change:[deg per second]''' +enums['MAV_CMD'][115].param[3] = '''direction: negative: counter clockwise, positive: clockwise [-1,1]''' +enums['MAV_CMD'][115].param[4] = '''relative offset or absolute angle: [ 1,0]''' +enums['MAV_CMD'][115].param[5] = '''Empty''' +enums['MAV_CMD'][115].param[6] = '''Empty''' +enums['MAV_CMD'][115].param[7] = '''Empty''' +MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the + # CONDITION commands in the enumeration +enums['MAV_CMD'][159] = EnumEntry('MAV_CMD_CONDITION_LAST', '''NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration''') +enums['MAV_CMD'][159].param[1] = '''Empty''' +enums['MAV_CMD'][159].param[2] = '''Empty''' +enums['MAV_CMD'][159].param[3] = '''Empty''' +enums['MAV_CMD'][159].param[4] = '''Empty''' +enums['MAV_CMD'][159].param[5] = '''Empty''' +enums['MAV_CMD'][159].param[6] = '''Empty''' +enums['MAV_CMD'][159].param[7] = '''Empty''' +MAV_CMD_DO_SET_MODE = 176 # Set system mode. +enums['MAV_CMD'][176] = EnumEntry('MAV_CMD_DO_SET_MODE', '''Set system mode.''') +enums['MAV_CMD'][176].param[1] = '''Mode, as defined by ENUM MAV_MODE''' +enums['MAV_CMD'][176].param[2] = '''Custom mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[3] = '''Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.''' +enums['MAV_CMD'][176].param[4] = '''Empty''' +enums['MAV_CMD'][176].param[5] = '''Empty''' +enums['MAV_CMD'][176].param[6] = '''Empty''' +enums['MAV_CMD'][176].param[7] = '''Empty''' +MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action + # only the specified number of times +enums['MAV_CMD'][177] = EnumEntry('MAV_CMD_DO_JUMP', '''Jump to the desired command in the mission list. Repeat this action only the specified number of times''') +enums['MAV_CMD'][177].param[1] = '''Sequence number''' +enums['MAV_CMD'][177].param[2] = '''Repeat count''' +enums['MAV_CMD'][177].param[3] = '''Empty''' +enums['MAV_CMD'][177].param[4] = '''Empty''' +enums['MAV_CMD'][177].param[5] = '''Empty''' +enums['MAV_CMD'][177].param[6] = '''Empty''' +enums['MAV_CMD'][177].param[7] = '''Empty''' +MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points. +enums['MAV_CMD'][178] = EnumEntry('MAV_CMD_DO_CHANGE_SPEED', '''Change speed and/or throttle set points.''') +enums['MAV_CMD'][178].param[1] = '''Speed type (0=Airspeed, 1=Ground Speed)''' +enums['MAV_CMD'][178].param[2] = '''Speed (m/s, -1 indicates no change)''' +enums['MAV_CMD'][178].param[3] = '''Throttle ( Percent, -1 indicates no change)''' +enums['MAV_CMD'][178].param[4] = '''Empty''' +enums['MAV_CMD'][178].param[5] = '''Empty''' +enums['MAV_CMD'][178].param[6] = '''Empty''' +enums['MAV_CMD'][178].param[7] = '''Empty''' +MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a + # specified location. +enums['MAV_CMD'][179] = EnumEntry('MAV_CMD_DO_SET_HOME', '''Changes the home location either to the current location or a specified location.''') +enums['MAV_CMD'][179].param[1] = '''Use current (1=use current location, 0=use specified location)''' +enums['MAV_CMD'][179].param[2] = '''Empty''' +enums['MAV_CMD'][179].param[3] = '''Empty''' +enums['MAV_CMD'][179].param[4] = '''Empty''' +enums['MAV_CMD'][179].param[5] = '''Latitude''' +enums['MAV_CMD'][179].param[6] = '''Longitude''' +enums['MAV_CMD'][179].param[7] = '''Altitude''' +MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires + # knowledge of the numeric enumeration value + # of the parameter. +enums['MAV_CMD'][180] = EnumEntry('MAV_CMD_DO_SET_PARAMETER', '''Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.''') +enums['MAV_CMD'][180].param[1] = '''Parameter number''' +enums['MAV_CMD'][180].param[2] = '''Parameter value''' +enums['MAV_CMD'][180].param[3] = '''Empty''' +enums['MAV_CMD'][180].param[4] = '''Empty''' +enums['MAV_CMD'][180].param[5] = '''Empty''' +enums['MAV_CMD'][180].param[6] = '''Empty''' +enums['MAV_CMD'][180].param[7] = '''Empty''' +MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition. +enums['MAV_CMD'][181] = EnumEntry('MAV_CMD_DO_SET_RELAY', '''Set a relay to a condition.''') +enums['MAV_CMD'][181].param[1] = '''Relay number''' +enums['MAV_CMD'][181].param[2] = '''Setting (1=on, 0=off, others possible depending on system hardware)''' +enums['MAV_CMD'][181].param[3] = '''Empty''' +enums['MAV_CMD'][181].param[4] = '''Empty''' +enums['MAV_CMD'][181].param[5] = '''Empty''' +enums['MAV_CMD'][181].param[6] = '''Empty''' +enums['MAV_CMD'][181].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired + # period. +enums['MAV_CMD'][182] = EnumEntry('MAV_CMD_DO_REPEAT_RELAY', '''Cycle a relay on and off for a desired number of cyles with a desired period.''') +enums['MAV_CMD'][182].param[1] = '''Relay number''' +enums['MAV_CMD'][182].param[2] = '''Cycle count''' +enums['MAV_CMD'][182].param[3] = '''Cycle time (seconds, decimal)''' +enums['MAV_CMD'][182].param[4] = '''Empty''' +enums['MAV_CMD'][182].param[5] = '''Empty''' +enums['MAV_CMD'][182].param[6] = '''Empty''' +enums['MAV_CMD'][182].param[7] = '''Empty''' +MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. +enums['MAV_CMD'][183] = EnumEntry('MAV_CMD_DO_SET_SERVO', '''Set a servo to a desired PWM value.''') +enums['MAV_CMD'][183].param[1] = '''Servo number''' +enums['MAV_CMD'][183].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][183].param[3] = '''Empty''' +enums['MAV_CMD'][183].param[4] = '''Empty''' +enums['MAV_CMD'][183].param[5] = '''Empty''' +enums['MAV_CMD'][183].param[6] = '''Empty''' +enums['MAV_CMD'][183].param[7] = '''Empty''' +MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired + # number of cycles with a desired period. +enums['MAV_CMD'][184] = EnumEntry('MAV_CMD_DO_REPEAT_SERVO', '''Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.''') +enums['MAV_CMD'][184].param[1] = '''Servo number''' +enums['MAV_CMD'][184].param[2] = '''PWM (microseconds, 1000 to 2000 typical)''' +enums['MAV_CMD'][184].param[3] = '''Cycle count''' +enums['MAV_CMD'][184].param[4] = '''Cycle time (seconds)''' +enums['MAV_CMD'][184].param[5] = '''Empty''' +enums['MAV_CMD'][184].param[6] = '''Empty''' +enums['MAV_CMD'][184].param[7] = '''Empty''' +MAV_CMD_DO_FLIGHTTERMINATION = 185 # Terminate flight immediately +enums['MAV_CMD'][185] = EnumEntry('MAV_CMD_DO_FLIGHTTERMINATION', '''Terminate flight immediately''') +enums['MAV_CMD'][185].param[1] = '''Flight termination activated if > 0.5''' +enums['MAV_CMD'][185].param[2] = '''Empty''' +enums['MAV_CMD'][185].param[3] = '''Empty''' +enums['MAV_CMD'][185].param[4] = '''Empty''' +enums['MAV_CMD'][185].param[5] = '''Empty''' +enums['MAV_CMD'][185].param[6] = '''Empty''' +enums['MAV_CMD'][185].param[7] = '''Empty''' +MAV_CMD_DO_LAND_START = 189 # Mission command to perform a landing. This is used as a marker in a + # mission to tell the autopilot where a + # sequence of mission items that represents a + # landing starts. It may also be sent via a + # COMMAND_LONG to trigger a landing, in which + # case the nearest (geographically) landing + # sequence in the mission will be used. The + # Latitude/Longitude is optional, and may be + # set to 0/0 if not needed. If specified then + # it will be used to help find the closest + # landing sequence. +enums['MAV_CMD'][189] = EnumEntry('MAV_CMD_DO_LAND_START', '''Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.''') +enums['MAV_CMD'][189].param[1] = '''Empty''' +enums['MAV_CMD'][189].param[2] = '''Empty''' +enums['MAV_CMD'][189].param[3] = '''Empty''' +enums['MAV_CMD'][189].param[4] = '''Empty''' +enums['MAV_CMD'][189].param[5] = '''Latitude''' +enums['MAV_CMD'][189].param[6] = '''Longitude''' +enums['MAV_CMD'][189].param[7] = '''Empty''' +MAV_CMD_DO_RALLY_LAND = 190 # Mission command to perform a landing from a rally point. +enums['MAV_CMD'][190] = EnumEntry('MAV_CMD_DO_RALLY_LAND', '''Mission command to perform a landing from a rally point.''') +enums['MAV_CMD'][190].param[1] = '''Break altitude (meters)''' +enums['MAV_CMD'][190].param[2] = '''Landing speed (m/s)''' +enums['MAV_CMD'][190].param[3] = '''Empty''' +enums['MAV_CMD'][190].param[4] = '''Empty''' +enums['MAV_CMD'][190].param[5] = '''Empty''' +enums['MAV_CMD'][190].param[6] = '''Empty''' +enums['MAV_CMD'][190].param[7] = '''Empty''' +MAV_CMD_DO_GO_AROUND = 191 # Mission command to safely abort an autonmous landing. +enums['MAV_CMD'][191] = EnumEntry('MAV_CMD_DO_GO_AROUND', '''Mission command to safely abort an autonmous landing.''') +enums['MAV_CMD'][191].param[1] = '''Altitude (meters)''' +enums['MAV_CMD'][191].param[2] = '''Empty''' +enums['MAV_CMD'][191].param[3] = '''Empty''' +enums['MAV_CMD'][191].param[4] = '''Empty''' +enums['MAV_CMD'][191].param[5] = '''Empty''' +enums['MAV_CMD'][191].param[6] = '''Empty''' +enums['MAV_CMD'][191].param[7] = '''Empty''' +MAV_CMD_DO_REPOSITION = 192 # Reposition the vehicle to a specific WGS84 global position. +enums['MAV_CMD'][192] = EnumEntry('MAV_CMD_DO_REPOSITION', '''Reposition the vehicle to a specific WGS84 global position.''') +enums['MAV_CMD'][192].param[1] = '''Ground speed, less than 0 (-1) for default''' +enums['MAV_CMD'][192].param[2] = '''Reserved''' +enums['MAV_CMD'][192].param[3] = '''Reserved''' +enums['MAV_CMD'][192].param[4] = '''Yaw heading, NaN for unchanged''' +enums['MAV_CMD'][192].param[5] = '''Latitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[6] = '''Longitude (deg * 1E7)''' +enums['MAV_CMD'][192].param[7] = '''Altitude (meters)''' +MAV_CMD_DO_PAUSE_CONTINUE = 193 # If in a GPS controlled position mode, hold the current position or + # continue. +enums['MAV_CMD'][193] = EnumEntry('MAV_CMD_DO_PAUSE_CONTINUE', '''If in a GPS controlled position mode, hold the current position or continue.''') +enums['MAV_CMD'][193].param[1] = '''0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.''' +enums['MAV_CMD'][193].param[2] = '''Reserved''' +enums['MAV_CMD'][193].param[3] = '''Reserved''' +enums['MAV_CMD'][193].param[4] = '''Reserved''' +enums['MAV_CMD'][193].param[5] = '''Reserved''' +enums['MAV_CMD'][193].param[6] = '''Reserved''' +enums['MAV_CMD'][193].param[7] = '''Reserved''' +MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. +enums['MAV_CMD'][200] = EnumEntry('MAV_CMD_DO_CONTROL_VIDEO', '''Control onboard camera system.''') +enums['MAV_CMD'][200].param[1] = '''Camera ID (-1 for all)''' +enums['MAV_CMD'][200].param[2] = '''Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[3] = '''Transmission mode: 0: video stream, >0: single images every n seconds (decimal)''' +enums['MAV_CMD'][200].param[4] = '''Recording: 0: disabled, 1: enabled compressed, 2: enabled raw''' +enums['MAV_CMD'][200].param[5] = '''Empty''' +enums['MAV_CMD'][200].param[6] = '''Empty''' +enums['MAV_CMD'][200].param[7] = '''Empty''' +MAV_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a sensor set or the vehicle + # itself. This can then be used by the + # vehicles control system to control the + # vehicle attitude and the attitude of various + # sensors such as cameras. +enums['MAV_CMD'][201] = EnumEntry('MAV_CMD_DO_SET_ROI', '''Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.''') +enums['MAV_CMD'][201].param[1] = '''Region of intereset mode. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[2] = '''MISSION index/ target ID. (see MAV_ROI enum)''' +enums['MAV_CMD'][201].param[3] = '''ROI index (allows a vehicle to manage multiple ROI's)''' +enums['MAV_CMD'][201].param[4] = '''Empty''' +enums['MAV_CMD'][201].param[5] = '''x the location of the fixed ROI (see MAV_FRAME)''' +enums['MAV_CMD'][201].param[6] = '''y''' +enums['MAV_CMD'][201].param[7] = '''z''' +MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system. +enums['MAV_CMD'][202] = EnumEntry('MAV_CMD_DO_DIGICAM_CONFIGURE', '''Mission command to configure an on-board camera controller system.''') +enums['MAV_CMD'][202].param[1] = '''Modes: P, TV, AV, M, Etc''' +enums['MAV_CMD'][202].param[2] = '''Shutter speed: Divisor number for one second''' +enums['MAV_CMD'][202].param[3] = '''Aperture: F stop number''' +enums['MAV_CMD'][202].param[4] = '''ISO number e.g. 80, 100, 200, Etc''' +enums['MAV_CMD'][202].param[5] = '''Exposure type enumerator''' +enums['MAV_CMD'][202].param[6] = '''Command Identity''' +enums['MAV_CMD'][202].param[7] = '''Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)''' +MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system. +enums['MAV_CMD'][203] = EnumEntry('MAV_CMD_DO_DIGICAM_CONTROL', '''Mission command to control an on-board camera controller system.''') +enums['MAV_CMD'][203].param[1] = '''Session control e.g. show/hide lens''' +enums['MAV_CMD'][203].param[2] = '''Zoom's absolute position''' +enums['MAV_CMD'][203].param[3] = '''Zooming step value to offset zoom from the current position''' +enums['MAV_CMD'][203].param[4] = '''Focus Locking, Unlocking or Re-locking''' +enums['MAV_CMD'][203].param[5] = '''Shooting Command''' +enums['MAV_CMD'][203].param[6] = '''Command Identity''' +enums['MAV_CMD'][203].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount +enums['MAV_CMD'][204] = EnumEntry('MAV_CMD_DO_MOUNT_CONFIGURE', '''Mission command to configure a camera or antenna mount''') +enums['MAV_CMD'][204].param[1] = '''Mount operation mode (see MAV_MOUNT_MODE enum)''' +enums['MAV_CMD'][204].param[2] = '''stabilize roll? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[3] = '''stabilize pitch? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[4] = '''stabilize yaw? (1 = yes, 0 = no)''' +enums['MAV_CMD'][204].param[5] = '''Empty''' +enums['MAV_CMD'][204].param[6] = '''Empty''' +enums['MAV_CMD'][204].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount +enums['MAV_CMD'][205] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL', '''Mission command to control a camera or antenna mount''') +enums['MAV_CMD'][205].param[1] = '''pitch or lat in degrees, depending on mount mode.''' +enums['MAV_CMD'][205].param[2] = '''roll or lon in degrees depending on mount mode''' +enums['MAV_CMD'][205].param[3] = '''yaw or alt (in meters) depending on mount mode''' +enums['MAV_CMD'][205].param[4] = '''reserved''' +enums['MAV_CMD'][205].param[5] = '''reserved''' +enums['MAV_CMD'][205].param[6] = '''reserved''' +enums['MAV_CMD'][205].param[7] = '''MAV_MOUNT_MODE enum value''' +MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206 # Mission command to set CAM_TRIGG_DIST for this flight +enums['MAV_CMD'][206] = EnumEntry('MAV_CMD_DO_SET_CAM_TRIGG_DIST', '''Mission command to set CAM_TRIGG_DIST for this flight''') +enums['MAV_CMD'][206].param[1] = '''Camera trigger distance (meters)''' +enums['MAV_CMD'][206].param[2] = '''Empty''' +enums['MAV_CMD'][206].param[3] = '''Empty''' +enums['MAV_CMD'][206].param[4] = '''Empty''' +enums['MAV_CMD'][206].param[5] = '''Empty''' +enums['MAV_CMD'][206].param[6] = '''Empty''' +enums['MAV_CMD'][206].param[7] = '''Empty''' +MAV_CMD_DO_FENCE_ENABLE = 207 # Mission command to enable the geofence +enums['MAV_CMD'][207] = EnumEntry('MAV_CMD_DO_FENCE_ENABLE', '''Mission command to enable the geofence''') +enums['MAV_CMD'][207].param[1] = '''enable? (0=disable, 1=enable, 2=disable_floor_only)''' +enums['MAV_CMD'][207].param[2] = '''Empty''' +enums['MAV_CMD'][207].param[3] = '''Empty''' +enums['MAV_CMD'][207].param[4] = '''Empty''' +enums['MAV_CMD'][207].param[5] = '''Empty''' +enums['MAV_CMD'][207].param[6] = '''Empty''' +enums['MAV_CMD'][207].param[7] = '''Empty''' +MAV_CMD_DO_PARACHUTE = 208 # Mission command to trigger a parachute +enums['MAV_CMD'][208] = EnumEntry('MAV_CMD_DO_PARACHUTE', '''Mission command to trigger a parachute''') +enums['MAV_CMD'][208].param[1] = '''action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)''' +enums['MAV_CMD'][208].param[2] = '''Empty''' +enums['MAV_CMD'][208].param[3] = '''Empty''' +enums['MAV_CMD'][208].param[4] = '''Empty''' +enums['MAV_CMD'][208].param[5] = '''Empty''' +enums['MAV_CMD'][208].param[6] = '''Empty''' +enums['MAV_CMD'][208].param[7] = '''Empty''' +MAV_CMD_DO_INVERTED_FLIGHT = 210 # Change to/from inverted flight +enums['MAV_CMD'][210] = EnumEntry('MAV_CMD_DO_INVERTED_FLIGHT', '''Change to/from inverted flight''') +enums['MAV_CMD'][210].param[1] = '''inverted (0=normal, 1=inverted)''' +enums['MAV_CMD'][210].param[2] = '''Empty''' +enums['MAV_CMD'][210].param[3] = '''Empty''' +enums['MAV_CMD'][210].param[4] = '''Empty''' +enums['MAV_CMD'][210].param[5] = '''Empty''' +enums['MAV_CMD'][210].param[6] = '''Empty''' +enums['MAV_CMD'][210].param[7] = '''Empty''' +MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 # Mission command to control a camera or antenna mount, using a + # quaternion as reference. +enums['MAV_CMD'][220] = EnumEntry('MAV_CMD_DO_MOUNT_CONTROL_QUAT', '''Mission command to control a camera or antenna mount, using a quaternion as reference.''') +enums['MAV_CMD'][220].param[1] = '''q1 - quaternion param #1, w (1 in null-rotation)''' +enums['MAV_CMD'][220].param[2] = '''q2 - quaternion param #2, x (0 in null-rotation)''' +enums['MAV_CMD'][220].param[3] = '''q3 - quaternion param #3, y (0 in null-rotation)''' +enums['MAV_CMD'][220].param[4] = '''q4 - quaternion param #4, z (0 in null-rotation)''' +enums['MAV_CMD'][220].param[5] = '''Empty''' +enums['MAV_CMD'][220].param[6] = '''Empty''' +enums['MAV_CMD'][220].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_MASTER = 221 # set id of master controller +enums['MAV_CMD'][221] = EnumEntry('MAV_CMD_DO_GUIDED_MASTER', '''set id of master controller''') +enums['MAV_CMD'][221].param[1] = '''System ID''' +enums['MAV_CMD'][221].param[2] = '''Component ID''' +enums['MAV_CMD'][221].param[3] = '''Empty''' +enums['MAV_CMD'][221].param[4] = '''Empty''' +enums['MAV_CMD'][221].param[5] = '''Empty''' +enums['MAV_CMD'][221].param[6] = '''Empty''' +enums['MAV_CMD'][221].param[7] = '''Empty''' +MAV_CMD_DO_GUIDED_LIMITS = 222 # set limits for external control +enums['MAV_CMD'][222] = EnumEntry('MAV_CMD_DO_GUIDED_LIMITS', '''set limits for external control''') +enums['MAV_CMD'][222].param[1] = '''timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout''' +enums['MAV_CMD'][222].param[2] = '''absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit''' +enums['MAV_CMD'][222].param[3] = '''absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit''' +enums['MAV_CMD'][222].param[4] = '''horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit''' +enums['MAV_CMD'][222].param[5] = '''Empty''' +enums['MAV_CMD'][222].param[6] = '''Empty''' +enums['MAV_CMD'][222].param[7] = '''Empty''' +MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO + # commands in the enumeration +enums['MAV_CMD'][240] = EnumEntry('MAV_CMD_DO_LAST', '''NOP - This command is only used to mark the upper limit of the DO commands in the enumeration''') +enums['MAV_CMD'][240].param[1] = '''Empty''' +enums['MAV_CMD'][240].param[2] = '''Empty''' +enums['MAV_CMD'][240].param[3] = '''Empty''' +enums['MAV_CMD'][240].param[4] = '''Empty''' +enums['MAV_CMD'][240].param[5] = '''Empty''' +enums['MAV_CMD'][240].param[6] = '''Empty''' +enums['MAV_CMD'][240].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][241] = EnumEntry('MAV_CMD_PREFLIGHT_CALIBRATION', '''Trigger calibration. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][241].param[1] = '''Gyro calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[2] = '''Magnetometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[3] = '''Ground pressure: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[4] = '''Radio calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[5] = '''Accelerometer calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[6] = '''Compass/Motor interference calibration: 0: no, 1: yes''' +enums['MAV_CMD'][241].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242 # Set sensor offsets. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][242] = EnumEntry('MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS', '''Set sensor offsets. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][242].param[1] = '''Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer''' +enums['MAV_CMD'][242].param[2] = '''X axis offset (or generic dimension 1), in the sensor's raw units''' +enums['MAV_CMD'][242].param[3] = '''Y axis offset (or generic dimension 2), in the sensor's raw units''' +enums['MAV_CMD'][242].param[4] = '''Z axis offset (or generic dimension 3), in the sensor's raw units''' +enums['MAV_CMD'][242].param[5] = '''Generic dimension 4, in the sensor's raw units''' +enums['MAV_CMD'][242].param[6] = '''Generic dimension 5, in the sensor's raw units''' +enums['MAV_CMD'][242].param[7] = '''Generic dimension 6, in the sensor's raw units''' +MAV_CMD_PREFLIGHT_UAVCAN = 243 # Trigger UAVCAN config. This command will be only accepted if in pre- + # flight mode. +enums['MAV_CMD'][243] = EnumEntry('MAV_CMD_PREFLIGHT_UAVCAN', '''Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][243].param[1] = '''1: Trigger actuator ID assignment and direction mapping.''' +enums['MAV_CMD'][243].param[2] = '''Reserved''' +enums['MAV_CMD'][243].param[3] = '''Reserved''' +enums['MAV_CMD'][243].param[4] = '''Reserved''' +enums['MAV_CMD'][243].param[5] = '''Reserved''' +enums['MAV_CMD'][243].param[6] = '''Reserved''' +enums['MAV_CMD'][243].param[7] = '''Reserved''' +MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command + # will be only accepted if in pre-flight mode. +enums['MAV_CMD'][245] = EnumEntry('MAV_CMD_PREFLIGHT_STORAGE', '''Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.''') +enums['MAV_CMD'][245].param[1] = '''Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[2] = '''Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults''' +enums['MAV_CMD'][245].param[3] = '''Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)''' +enums['MAV_CMD'][245].param[4] = '''Reserved''' +enums['MAV_CMD'][245].param[5] = '''Empty''' +enums['MAV_CMD'][245].param[6] = '''Empty''' +enums['MAV_CMD'][245].param[7] = '''Empty''' +MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246 # Request the reboot or shutdown of system components. +enums['MAV_CMD'][246] = EnumEntry('MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN', '''Request the reboot or shutdown of system components.''') +enums['MAV_CMD'][246].param[1] = '''0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[2] = '''0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.''' +enums['MAV_CMD'][246].param[3] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[4] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[5] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[6] = '''Reserved, send 0''' +enums['MAV_CMD'][246].param[7] = '''Reserved, send 0''' +MAV_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action +enums['MAV_CMD'][252] = EnumEntry('MAV_CMD_OVERRIDE_GOTO', '''Hold / continue the current action''') +enums['MAV_CMD'][252].param[1] = '''MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan''' +enums['MAV_CMD'][252].param[2] = '''MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position''' +enums['MAV_CMD'][252].param[3] = '''MAV_FRAME coordinate frame of hold point''' +enums['MAV_CMD'][252].param[4] = '''Desired yaw angle in degrees''' +enums['MAV_CMD'][252].param[5] = '''Latitude / X position''' +enums['MAV_CMD'][252].param[6] = '''Longitude / Y position''' +enums['MAV_CMD'][252].param[7] = '''Altitude / Z position''' +MAV_CMD_MISSION_START = 300 # start running a mission +enums['MAV_CMD'][300] = EnumEntry('MAV_CMD_MISSION_START', '''start running a mission''') +enums['MAV_CMD'][300].param[1] = '''first_item: the first mission item to run''' +enums['MAV_CMD'][300].param[2] = '''last_item: the last mission item to run (after this item is run, the mission ends)''' +MAV_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component +enums['MAV_CMD'][400] = EnumEntry('MAV_CMD_COMPONENT_ARM_DISARM', '''Arms / Disarms a component''') +enums['MAV_CMD'][400].param[1] = '''1 to arm, 0 to disarm''' +MAV_CMD_GET_HOME_POSITION = 410 # Request the home position from the vehicle. +enums['MAV_CMD'][410] = EnumEntry('MAV_CMD_GET_HOME_POSITION', '''Request the home position from the vehicle.''') +enums['MAV_CMD'][410].param[1] = '''Reserved''' +enums['MAV_CMD'][410].param[2] = '''Reserved''' +enums['MAV_CMD'][410].param[3] = '''Reserved''' +enums['MAV_CMD'][410].param[4] = '''Reserved''' +enums['MAV_CMD'][410].param[5] = '''Reserved''' +enums['MAV_CMD'][410].param[6] = '''Reserved''' +enums['MAV_CMD'][410].param[7] = '''Reserved''' +MAV_CMD_START_RX_PAIR = 500 # Starts receiver pairing +enums['MAV_CMD'][500] = EnumEntry('MAV_CMD_START_RX_PAIR', '''Starts receiver pairing''') +enums['MAV_CMD'][500].param[1] = '''0:Spektrum''' +enums['MAV_CMD'][500].param[2] = '''0:Spektrum DSM2, 1:Spektrum DSMX''' +MAV_CMD_GET_MESSAGE_INTERVAL = 510 # Request the interval between messages for a particular MAVLink message + # ID +enums['MAV_CMD'][510] = EnumEntry('MAV_CMD_GET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID''') +enums['MAV_CMD'][510].param[1] = '''The MAVLink message ID''' +MAV_CMD_SET_MESSAGE_INTERVAL = 511 # Request the interval between messages for a particular MAVLink message + # ID. This interface replaces + # REQUEST_DATA_STREAM +enums['MAV_CMD'][511] = EnumEntry('MAV_CMD_SET_MESSAGE_INTERVAL', '''Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM''') +enums['MAV_CMD'][511].param[1] = '''The MAVLink message ID''' +enums['MAV_CMD'][511].param[2] = '''The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.''' +MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520 # Request autopilot capabilities +enums['MAV_CMD'][520] = EnumEntry('MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES', '''Request autopilot capabilities''') +enums['MAV_CMD'][520].param[1] = '''1: Request autopilot version''' +enums['MAV_CMD'][520].param[2] = '''Reserved (all remaining params)''' +MAV_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence +enums['MAV_CMD'][2000] = EnumEntry('MAV_CMD_IMAGE_START_CAPTURE', '''Start image capture sequence''') +enums['MAV_CMD'][2000].param[1] = '''Duration between two consecutive pictures (in seconds)''' +enums['MAV_CMD'][2000].param[2] = '''Number of images to capture total - 0 for unlimited capture''' +enums['MAV_CMD'][2000].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_IMAGE_STOP_CAPTURE = 2001 # Stop image capture sequence +enums['MAV_CMD'][2001] = EnumEntry('MAV_CMD_IMAGE_STOP_CAPTURE', '''Stop image capture sequence''') +enums['MAV_CMD'][2001].param[1] = '''Reserved''' +enums['MAV_CMD'][2001].param[2] = '''Reserved''' +MAV_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system. +enums['MAV_CMD'][2003] = EnumEntry('MAV_CMD_DO_TRIGGER_CONTROL', '''Enable or disable on-board camera triggering system.''') +enums['MAV_CMD'][2003].param[1] = '''Trigger enable/disable (0 for disable, 1 for start)''' +enums['MAV_CMD'][2003].param[2] = '''Shutter integration time (in ms)''' +enums['MAV_CMD'][2003].param[3] = '''Reserved''' +MAV_CMD_VIDEO_START_CAPTURE = 2500 # Starts video capture +enums['MAV_CMD'][2500] = EnumEntry('MAV_CMD_VIDEO_START_CAPTURE', '''Starts video capture''') +enums['MAV_CMD'][2500].param[1] = '''Camera ID (0 for all cameras), 1 for first, 2 for second, etc.''' +enums['MAV_CMD'][2500].param[2] = '''Frames per second''' +enums['MAV_CMD'][2500].param[3] = '''Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)''' +MAV_CMD_VIDEO_STOP_CAPTURE = 2501 # Stop the current video capture +enums['MAV_CMD'][2501] = EnumEntry('MAV_CMD_VIDEO_STOP_CAPTURE', '''Stop the current video capture''') +enums['MAV_CMD'][2501].param[1] = '''Reserved''' +enums['MAV_CMD'][2501].param[2] = '''Reserved''' +MAV_CMD_PANORAMA_CREATE = 2800 # Create a panorama at the current position +enums['MAV_CMD'][2800] = EnumEntry('MAV_CMD_PANORAMA_CREATE', '''Create a panorama at the current position''') +enums['MAV_CMD'][2800].param[1] = '''Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)''' +enums['MAV_CMD'][2800].param[2] = '''Viewing angle vertical of panorama (in degrees)''' +enums['MAV_CMD'][2800].param[3] = '''Speed of the horizontal rotation (in degrees per second)''' +enums['MAV_CMD'][2800].param[4] = '''Speed of the vertical rotation (in degrees per second)''' +MAV_CMD_DO_VTOL_TRANSITION = 3000 # Request VTOL transition +enums['MAV_CMD'][3000] = EnumEntry('MAV_CMD_DO_VTOL_TRANSITION', '''Request VTOL transition''') +enums['MAV_CMD'][3000].param[1] = '''The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.''' +MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Deploy payload on a Lat / Lon / Alt position. This includes the + # navigation to reach the required release + # position and velocity. +enums['MAV_CMD'][30001] = EnumEntry('MAV_CMD_PAYLOAD_PREPARE_DEPLOY', '''Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.''') +enums['MAV_CMD'][30001].param[1] = '''Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.''' +enums['MAV_CMD'][30001].param[2] = '''Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.''' +enums['MAV_CMD'][30001].param[3] = '''Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.''' +enums['MAV_CMD'][30001].param[4] = '''Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.''' +enums['MAV_CMD'][30001].param[5] = '''Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[6] = '''Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT''' +enums['MAV_CMD'][30001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 # Control the payload deployment. +enums['MAV_CMD'][30002] = EnumEntry('MAV_CMD_PAYLOAD_CONTROL_DEPLOY', '''Control the payload deployment.''') +enums['MAV_CMD'][30002].param[1] = '''Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.''' +enums['MAV_CMD'][30002].param[2] = '''Reserved''' +enums['MAV_CMD'][30002].param[3] = '''Reserved''' +enums['MAV_CMD'][30002].param[4] = '''Reserved''' +enums['MAV_CMD'][30002].param[5] = '''Reserved''' +enums['MAV_CMD'][30002].param[6] = '''Reserved''' +enums['MAV_CMD'][30002].param[7] = '''Reserved''' +MAV_CMD_WAYPOINT_USER_1 = 31000 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31000] = EnumEntry('MAV_CMD_WAYPOINT_USER_1', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31000].param[1] = '''User defined''' +enums['MAV_CMD'][31000].param[2] = '''User defined''' +enums['MAV_CMD'][31000].param[3] = '''User defined''' +enums['MAV_CMD'][31000].param[4] = '''User defined''' +enums['MAV_CMD'][31000].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31000].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31000].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_2 = 31001 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31001] = EnumEntry('MAV_CMD_WAYPOINT_USER_2', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31001].param[1] = '''User defined''' +enums['MAV_CMD'][31001].param[2] = '''User defined''' +enums['MAV_CMD'][31001].param[3] = '''User defined''' +enums['MAV_CMD'][31001].param[4] = '''User defined''' +enums['MAV_CMD'][31001].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31001].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31001].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_3 = 31002 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31002] = EnumEntry('MAV_CMD_WAYPOINT_USER_3', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31002].param[1] = '''User defined''' +enums['MAV_CMD'][31002].param[2] = '''User defined''' +enums['MAV_CMD'][31002].param[3] = '''User defined''' +enums['MAV_CMD'][31002].param[4] = '''User defined''' +enums['MAV_CMD'][31002].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31002].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31002].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_4 = 31003 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31003] = EnumEntry('MAV_CMD_WAYPOINT_USER_4', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31003].param[1] = '''User defined''' +enums['MAV_CMD'][31003].param[2] = '''User defined''' +enums['MAV_CMD'][31003].param[3] = '''User defined''' +enums['MAV_CMD'][31003].param[4] = '''User defined''' +enums['MAV_CMD'][31003].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31003].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31003].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_WAYPOINT_USER_5 = 31004 # User defined waypoint item. Ground Station will show the Vehicle as + # flying through this item. +enums['MAV_CMD'][31004] = EnumEntry('MAV_CMD_WAYPOINT_USER_5', '''User defined waypoint item. Ground Station will show the Vehicle as flying through this item.''') +enums['MAV_CMD'][31004].param[1] = '''User defined''' +enums['MAV_CMD'][31004].param[2] = '''User defined''' +enums['MAV_CMD'][31004].param[3] = '''User defined''' +enums['MAV_CMD'][31004].param[4] = '''User defined''' +enums['MAV_CMD'][31004].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31004].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31004].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_1 = 31005 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31005] = EnumEntry('MAV_CMD_SPATIAL_USER_1', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31005].param[1] = '''User defined''' +enums['MAV_CMD'][31005].param[2] = '''User defined''' +enums['MAV_CMD'][31005].param[3] = '''User defined''' +enums['MAV_CMD'][31005].param[4] = '''User defined''' +enums['MAV_CMD'][31005].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31005].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31005].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_2 = 31006 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31006] = EnumEntry('MAV_CMD_SPATIAL_USER_2', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31006].param[1] = '''User defined''' +enums['MAV_CMD'][31006].param[2] = '''User defined''' +enums['MAV_CMD'][31006].param[3] = '''User defined''' +enums['MAV_CMD'][31006].param[4] = '''User defined''' +enums['MAV_CMD'][31006].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31006].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31006].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_3 = 31007 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31007] = EnumEntry('MAV_CMD_SPATIAL_USER_3', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31007].param[1] = '''User defined''' +enums['MAV_CMD'][31007].param[2] = '''User defined''' +enums['MAV_CMD'][31007].param[3] = '''User defined''' +enums['MAV_CMD'][31007].param[4] = '''User defined''' +enums['MAV_CMD'][31007].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31007].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31007].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_4 = 31008 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31008] = EnumEntry('MAV_CMD_SPATIAL_USER_4', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31008].param[1] = '''User defined''' +enums['MAV_CMD'][31008].param[2] = '''User defined''' +enums['MAV_CMD'][31008].param[3] = '''User defined''' +enums['MAV_CMD'][31008].param[4] = '''User defined''' +enums['MAV_CMD'][31008].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31008].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31008].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_SPATIAL_USER_5 = 31009 # User defined spatial item. Ground Station will not show the Vehicle as + # flying through this item. Example: ROI item. +enums['MAV_CMD'][31009] = EnumEntry('MAV_CMD_SPATIAL_USER_5', '''User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.''') +enums['MAV_CMD'][31009].param[1] = '''User defined''' +enums['MAV_CMD'][31009].param[2] = '''User defined''' +enums['MAV_CMD'][31009].param[3] = '''User defined''' +enums['MAV_CMD'][31009].param[4] = '''User defined''' +enums['MAV_CMD'][31009].param[5] = '''Latitude unscaled''' +enums['MAV_CMD'][31009].param[6] = '''Longitude unscaled''' +enums['MAV_CMD'][31009].param[7] = '''Altitude, in meters AMSL''' +MAV_CMD_USER_1 = 31010 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31010] = EnumEntry('MAV_CMD_USER_1', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31010].param[1] = '''User defined''' +enums['MAV_CMD'][31010].param[2] = '''User defined''' +enums['MAV_CMD'][31010].param[3] = '''User defined''' +enums['MAV_CMD'][31010].param[4] = '''User defined''' +enums['MAV_CMD'][31010].param[5] = '''User defined''' +enums['MAV_CMD'][31010].param[6] = '''User defined''' +enums['MAV_CMD'][31010].param[7] = '''User defined''' +MAV_CMD_USER_2 = 31011 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31011] = EnumEntry('MAV_CMD_USER_2', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31011].param[1] = '''User defined''' +enums['MAV_CMD'][31011].param[2] = '''User defined''' +enums['MAV_CMD'][31011].param[3] = '''User defined''' +enums['MAV_CMD'][31011].param[4] = '''User defined''' +enums['MAV_CMD'][31011].param[5] = '''User defined''' +enums['MAV_CMD'][31011].param[6] = '''User defined''' +enums['MAV_CMD'][31011].param[7] = '''User defined''' +MAV_CMD_USER_3 = 31012 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31012] = EnumEntry('MAV_CMD_USER_3', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31012].param[1] = '''User defined''' +enums['MAV_CMD'][31012].param[2] = '''User defined''' +enums['MAV_CMD'][31012].param[3] = '''User defined''' +enums['MAV_CMD'][31012].param[4] = '''User defined''' +enums['MAV_CMD'][31012].param[5] = '''User defined''' +enums['MAV_CMD'][31012].param[6] = '''User defined''' +enums['MAV_CMD'][31012].param[7] = '''User defined''' +MAV_CMD_USER_4 = 31013 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31013] = EnumEntry('MAV_CMD_USER_4', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31013].param[1] = '''User defined''' +enums['MAV_CMD'][31013].param[2] = '''User defined''' +enums['MAV_CMD'][31013].param[3] = '''User defined''' +enums['MAV_CMD'][31013].param[4] = '''User defined''' +enums['MAV_CMD'][31013].param[5] = '''User defined''' +enums['MAV_CMD'][31013].param[6] = '''User defined''' +enums['MAV_CMD'][31013].param[7] = '''User defined''' +MAV_CMD_USER_5 = 31014 # User defined command. Ground Station will not show the Vehicle as + # flying through this item. Example: + # MAV_CMD_DO_SET_PARAMETER item. +enums['MAV_CMD'][31014] = EnumEntry('MAV_CMD_USER_5', '''User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.''') +enums['MAV_CMD'][31014].param[1] = '''User defined''' +enums['MAV_CMD'][31014].param[2] = '''User defined''' +enums['MAV_CMD'][31014].param[3] = '''User defined''' +enums['MAV_CMD'][31014].param[4] = '''User defined''' +enums['MAV_CMD'][31014].param[5] = '''User defined''' +enums['MAV_CMD'][31014].param[6] = '''User defined''' +enums['MAV_CMD'][31014].param[7] = '''User defined''' +MAV_CMD_ENUM_END = 31015 # +enums['MAV_CMD'][31015] = EnumEntry('MAV_CMD_ENUM_END', '''''') + +# MAV_DATA_STREAM +enums['MAV_DATA_STREAM'] = {} +MAV_DATA_STREAM_ALL = 0 # Enable all data streams +enums['MAV_DATA_STREAM'][0] = EnumEntry('MAV_DATA_STREAM_ALL', '''Enable all data streams''') +MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. +enums['MAV_DATA_STREAM'][1] = EnumEntry('MAV_DATA_STREAM_RAW_SENSORS', '''Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.''') +MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS +enums['MAV_DATA_STREAM'][2] = EnumEntry('MAV_DATA_STREAM_EXTENDED_STATUS', '''Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS''') +MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW +enums['MAV_DATA_STREAM'][3] = EnumEntry('MAV_DATA_STREAM_RC_CHANNELS', '''Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW''') +MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, + # NAV_CONTROLLER_OUTPUT. +enums['MAV_DATA_STREAM'][4] = EnumEntry('MAV_DATA_STREAM_RAW_CONTROLLER', '''Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.''') +MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. +enums['MAV_DATA_STREAM'][6] = EnumEntry('MAV_DATA_STREAM_POSITION', '''Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.''') +MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][10] = EnumEntry('MAV_DATA_STREAM_EXTRA1', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][11] = EnumEntry('MAV_DATA_STREAM_EXTRA2', '''Dependent on the autopilot''') +MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot +enums['MAV_DATA_STREAM'][12] = EnumEntry('MAV_DATA_STREAM_EXTRA3', '''Dependent on the autopilot''') +MAV_DATA_STREAM_ENUM_END = 13 # +enums['MAV_DATA_STREAM'][13] = EnumEntry('MAV_DATA_STREAM_ENUM_END', '''''') + +# MAV_ROI +enums['MAV_ROI'] = {} +MAV_ROI_NONE = 0 # No region of interest. +enums['MAV_ROI'][0] = EnumEntry('MAV_ROI_NONE', '''No region of interest.''') +MAV_ROI_WPNEXT = 1 # Point toward next MISSION. +enums['MAV_ROI'][1] = EnumEntry('MAV_ROI_WPNEXT', '''Point toward next MISSION.''') +MAV_ROI_WPINDEX = 2 # Point toward given MISSION. +enums['MAV_ROI'][2] = EnumEntry('MAV_ROI_WPINDEX', '''Point toward given MISSION.''') +MAV_ROI_LOCATION = 3 # Point toward fixed location. +enums['MAV_ROI'][3] = EnumEntry('MAV_ROI_LOCATION', '''Point toward fixed location.''') +MAV_ROI_TARGET = 4 # Point toward of given id. +enums['MAV_ROI'][4] = EnumEntry('MAV_ROI_TARGET', '''Point toward of given id.''') +MAV_ROI_ENUM_END = 5 # +enums['MAV_ROI'][5] = EnumEntry('MAV_ROI_ENUM_END', '''''') + +# MAV_CMD_ACK +enums['MAV_CMD_ACK'] = {} +MAV_CMD_ACK_OK = 1 # Command / mission item is ok. +enums['MAV_CMD_ACK'][1] = EnumEntry('MAV_CMD_ACK_OK', '''Command / mission item is ok.''') +MAV_CMD_ACK_ERR_FAIL = 2 # Generic error message if none of the other reasons fails or if no + # detailed error reporting is implemented. +enums['MAV_CMD_ACK'][2] = EnumEntry('MAV_CMD_ACK_ERR_FAIL', '''Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.''') +MAV_CMD_ACK_ERR_ACCESS_DENIED = 3 # The system is refusing to accept this command from this source / + # communication partner. +enums['MAV_CMD_ACK'][3] = EnumEntry('MAV_CMD_ACK_ERR_ACCESS_DENIED', '''The system is refusing to accept this command from this source / communication partner.''') +MAV_CMD_ACK_ERR_NOT_SUPPORTED = 4 # Command or mission item is not supported, other commands would be + # accepted. +enums['MAV_CMD_ACK'][4] = EnumEntry('MAV_CMD_ACK_ERR_NOT_SUPPORTED', '''Command or mission item is not supported, other commands would be accepted.''') +MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 5 # The coordinate frame of this command / mission item is not supported. +enums['MAV_CMD_ACK'][5] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED', '''The coordinate frame of this command / mission item is not supported.''') +MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 6 # 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. +enums['MAV_CMD_ACK'][6] = EnumEntry('MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE', '''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.''') +MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 7 # The X or latitude value is out of range. +enums['MAV_CMD_ACK'][7] = EnumEntry('MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE', '''The X or latitude value is out of range.''') +MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 8 # The Y or longitude value is out of range. +enums['MAV_CMD_ACK'][8] = EnumEntry('MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE', '''The Y or longitude value is out of range.''') +MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 9 # The Z or altitude value is out of range. +enums['MAV_CMD_ACK'][9] = EnumEntry('MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE', '''The Z or altitude value is out of range.''') +MAV_CMD_ACK_ENUM_END = 10 # +enums['MAV_CMD_ACK'][10] = EnumEntry('MAV_CMD_ACK_ENUM_END', '''''') + +# MAV_PARAM_TYPE +enums['MAV_PARAM_TYPE'] = {} +MAV_PARAM_TYPE_UINT8 = 1 # 8-bit unsigned integer +enums['MAV_PARAM_TYPE'][1] = EnumEntry('MAV_PARAM_TYPE_UINT8', '''8-bit unsigned integer''') +MAV_PARAM_TYPE_INT8 = 2 # 8-bit signed integer +enums['MAV_PARAM_TYPE'][2] = EnumEntry('MAV_PARAM_TYPE_INT8', '''8-bit signed integer''') +MAV_PARAM_TYPE_UINT16 = 3 # 16-bit unsigned integer +enums['MAV_PARAM_TYPE'][3] = EnumEntry('MAV_PARAM_TYPE_UINT16', '''16-bit unsigned integer''') +MAV_PARAM_TYPE_INT16 = 4 # 16-bit signed integer +enums['MAV_PARAM_TYPE'][4] = EnumEntry('MAV_PARAM_TYPE_INT16', '''16-bit signed integer''') +MAV_PARAM_TYPE_UINT32 = 5 # 32-bit unsigned integer +enums['MAV_PARAM_TYPE'][5] = EnumEntry('MAV_PARAM_TYPE_UINT32', '''32-bit unsigned integer''') +MAV_PARAM_TYPE_INT32 = 6 # 32-bit signed integer +enums['MAV_PARAM_TYPE'][6] = EnumEntry('MAV_PARAM_TYPE_INT32', '''32-bit signed integer''') +MAV_PARAM_TYPE_UINT64 = 7 # 64-bit unsigned integer +enums['MAV_PARAM_TYPE'][7] = EnumEntry('MAV_PARAM_TYPE_UINT64', '''64-bit unsigned integer''') +MAV_PARAM_TYPE_INT64 = 8 # 64-bit signed integer +enums['MAV_PARAM_TYPE'][8] = EnumEntry('MAV_PARAM_TYPE_INT64', '''64-bit signed integer''') +MAV_PARAM_TYPE_REAL32 = 9 # 32-bit floating-point +enums['MAV_PARAM_TYPE'][9] = EnumEntry('MAV_PARAM_TYPE_REAL32', '''32-bit floating-point''') +MAV_PARAM_TYPE_REAL64 = 10 # 64-bit floating-point +enums['MAV_PARAM_TYPE'][10] = EnumEntry('MAV_PARAM_TYPE_REAL64', '''64-bit floating-point''') +MAV_PARAM_TYPE_ENUM_END = 11 # +enums['MAV_PARAM_TYPE'][11] = EnumEntry('MAV_PARAM_TYPE_ENUM_END', '''''') + +# MAV_RESULT +enums['MAV_RESULT'] = {} +MAV_RESULT_ACCEPTED = 0 # Command ACCEPTED and EXECUTED +enums['MAV_RESULT'][0] = EnumEntry('MAV_RESULT_ACCEPTED', '''Command ACCEPTED and EXECUTED''') +MAV_RESULT_TEMPORARILY_REJECTED = 1 # Command TEMPORARY REJECTED/DENIED +enums['MAV_RESULT'][1] = EnumEntry('MAV_RESULT_TEMPORARILY_REJECTED', '''Command TEMPORARY REJECTED/DENIED''') +MAV_RESULT_DENIED = 2 # Command PERMANENTLY DENIED +enums['MAV_RESULT'][2] = EnumEntry('MAV_RESULT_DENIED', '''Command PERMANENTLY DENIED''') +MAV_RESULT_UNSUPPORTED = 3 # Command UNKNOWN/UNSUPPORTED +enums['MAV_RESULT'][3] = EnumEntry('MAV_RESULT_UNSUPPORTED', '''Command UNKNOWN/UNSUPPORTED''') +MAV_RESULT_FAILED = 4 # Command executed, but failed +enums['MAV_RESULT'][4] = EnumEntry('MAV_RESULT_FAILED', '''Command executed, but failed''') +MAV_RESULT_ENUM_END = 5 # +enums['MAV_RESULT'][5] = EnumEntry('MAV_RESULT_ENUM_END', '''''') + +# MAV_MISSION_RESULT +enums['MAV_MISSION_RESULT'] = {} +MAV_MISSION_ACCEPTED = 0 # mission accepted OK +enums['MAV_MISSION_RESULT'][0] = EnumEntry('MAV_MISSION_ACCEPTED', '''mission accepted OK''') +MAV_MISSION_ERROR = 1 # generic error / not accepting mission commands at all right now +enums['MAV_MISSION_RESULT'][1] = EnumEntry('MAV_MISSION_ERROR', '''generic error / not accepting mission commands at all right now''') +MAV_MISSION_UNSUPPORTED_FRAME = 2 # coordinate frame is not supported +enums['MAV_MISSION_RESULT'][2] = EnumEntry('MAV_MISSION_UNSUPPORTED_FRAME', '''coordinate frame is not supported''') +MAV_MISSION_UNSUPPORTED = 3 # command is not supported +enums['MAV_MISSION_RESULT'][3] = EnumEntry('MAV_MISSION_UNSUPPORTED', '''command is not supported''') +MAV_MISSION_NO_SPACE = 4 # mission item exceeds storage space +enums['MAV_MISSION_RESULT'][4] = EnumEntry('MAV_MISSION_NO_SPACE', '''mission item exceeds storage space''') +MAV_MISSION_INVALID = 5 # one of the parameters has an invalid value +enums['MAV_MISSION_RESULT'][5] = EnumEntry('MAV_MISSION_INVALID', '''one of the parameters has an invalid value''') +MAV_MISSION_INVALID_PARAM1 = 6 # param1 has an invalid value +enums['MAV_MISSION_RESULT'][6] = EnumEntry('MAV_MISSION_INVALID_PARAM1', '''param1 has an invalid value''') +MAV_MISSION_INVALID_PARAM2 = 7 # param2 has an invalid value +enums['MAV_MISSION_RESULT'][7] = EnumEntry('MAV_MISSION_INVALID_PARAM2', '''param2 has an invalid value''') +MAV_MISSION_INVALID_PARAM3 = 8 # param3 has an invalid value +enums['MAV_MISSION_RESULT'][8] = EnumEntry('MAV_MISSION_INVALID_PARAM3', '''param3 has an invalid value''') +MAV_MISSION_INVALID_PARAM4 = 9 # param4 has an invalid value +enums['MAV_MISSION_RESULT'][9] = EnumEntry('MAV_MISSION_INVALID_PARAM4', '''param4 has an invalid value''') +MAV_MISSION_INVALID_PARAM5_X = 10 # x/param5 has an invalid value +enums['MAV_MISSION_RESULT'][10] = EnumEntry('MAV_MISSION_INVALID_PARAM5_X', '''x/param5 has an invalid value''') +MAV_MISSION_INVALID_PARAM6_Y = 11 # y/param6 has an invalid value +enums['MAV_MISSION_RESULT'][11] = EnumEntry('MAV_MISSION_INVALID_PARAM6_Y', '''y/param6 has an invalid value''') +MAV_MISSION_INVALID_PARAM7 = 12 # param7 has an invalid value +enums['MAV_MISSION_RESULT'][12] = EnumEntry('MAV_MISSION_INVALID_PARAM7', '''param7 has an invalid value''') +MAV_MISSION_INVALID_SEQUENCE = 13 # received waypoint out of sequence +enums['MAV_MISSION_RESULT'][13] = EnumEntry('MAV_MISSION_INVALID_SEQUENCE', '''received waypoint out of sequence''') +MAV_MISSION_DENIED = 14 # not accepting any mission commands from this communication partner +enums['MAV_MISSION_RESULT'][14] = EnumEntry('MAV_MISSION_DENIED', '''not accepting any mission commands from this communication partner''') +MAV_MISSION_RESULT_ENUM_END = 15 # +enums['MAV_MISSION_RESULT'][15] = EnumEntry('MAV_MISSION_RESULT_ENUM_END', '''''') + +# MAV_SEVERITY +enums['MAV_SEVERITY'] = {} +MAV_SEVERITY_EMERGENCY = 0 # System is unusable. This is a "panic" condition. +enums['MAV_SEVERITY'][0] = EnumEntry('MAV_SEVERITY_EMERGENCY', '''System is unusable. This is a "panic" condition.''') +MAV_SEVERITY_ALERT = 1 # Action should be taken immediately. Indicates error in non-critical + # systems. +enums['MAV_SEVERITY'][1] = EnumEntry('MAV_SEVERITY_ALERT', '''Action should be taken immediately. Indicates error in non-critical systems.''') +MAV_SEVERITY_CRITICAL = 2 # Action must be taken immediately. Indicates failure in a primary + # system. +enums['MAV_SEVERITY'][2] = EnumEntry('MAV_SEVERITY_CRITICAL', '''Action must be taken immediately. Indicates failure in a primary system.''') +MAV_SEVERITY_ERROR = 3 # Indicates an error in secondary/redundant systems. +enums['MAV_SEVERITY'][3] = EnumEntry('MAV_SEVERITY_ERROR', '''Indicates an error in secondary/redundant systems.''') +MAV_SEVERITY_WARNING = 4 # Indicates about a possible future error if this is not resolved within + # a given timeframe. Example would be a low + # battery warning. +enums['MAV_SEVERITY'][4] = EnumEntry('MAV_SEVERITY_WARNING', '''Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.''') +MAV_SEVERITY_NOTICE = 5 # An unusual event has occured, though not an error condition. This + # should be investigated for the root cause. +enums['MAV_SEVERITY'][5] = EnumEntry('MAV_SEVERITY_NOTICE', '''An unusual event has occured, though not an error condition. This should be investigated for the root cause.''') +MAV_SEVERITY_INFO = 6 # Normal operational messages. Useful for logging. No action is required + # for these messages. +enums['MAV_SEVERITY'][6] = EnumEntry('MAV_SEVERITY_INFO', '''Normal operational messages. Useful for logging. No action is required for these messages.''') +MAV_SEVERITY_DEBUG = 7 # Useful non-operational messages that can assist in debugging. These + # should not occur during normal operation. +enums['MAV_SEVERITY'][7] = EnumEntry('MAV_SEVERITY_DEBUG', '''Useful non-operational messages that can assist in debugging. These should not occur during normal operation.''') +MAV_SEVERITY_ENUM_END = 8 # +enums['MAV_SEVERITY'][8] = EnumEntry('MAV_SEVERITY_ENUM_END', '''''') + +# MAV_POWER_STATUS +enums['MAV_POWER_STATUS'] = {} +MAV_POWER_STATUS_BRICK_VALID = 1 # main brick power supply valid +enums['MAV_POWER_STATUS'][1] = EnumEntry('MAV_POWER_STATUS_BRICK_VALID', '''main brick power supply valid''') +MAV_POWER_STATUS_SERVO_VALID = 2 # main servo power supply valid for FMU +enums['MAV_POWER_STATUS'][2] = EnumEntry('MAV_POWER_STATUS_SERVO_VALID', '''main servo power supply valid for FMU''') +MAV_POWER_STATUS_USB_CONNECTED = 4 # USB power is connected +enums['MAV_POWER_STATUS'][4] = EnumEntry('MAV_POWER_STATUS_USB_CONNECTED', '''USB power is connected''') +MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 # peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][8] = EnumEntry('MAV_POWER_STATUS_PERIPH_OVERCURRENT', '''peripheral supply is in over-current state''') +MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 # hi-power peripheral supply is in over-current state +enums['MAV_POWER_STATUS'][16] = EnumEntry('MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT', '''hi-power peripheral supply is in over-current state''') +MAV_POWER_STATUS_CHANGED = 32 # Power status has changed since boot +enums['MAV_POWER_STATUS'][32] = EnumEntry('MAV_POWER_STATUS_CHANGED', '''Power status has changed since boot''') +MAV_POWER_STATUS_ENUM_END = 33 # +enums['MAV_POWER_STATUS'][33] = EnumEntry('MAV_POWER_STATUS_ENUM_END', '''''') + +# SERIAL_CONTROL_DEV +enums['SERIAL_CONTROL_DEV'] = {} +SERIAL_CONTROL_DEV_TELEM1 = 0 # First telemetry port +enums['SERIAL_CONTROL_DEV'][0] = EnumEntry('SERIAL_CONTROL_DEV_TELEM1', '''First telemetry port''') +SERIAL_CONTROL_DEV_TELEM2 = 1 # Second telemetry port +enums['SERIAL_CONTROL_DEV'][1] = EnumEntry('SERIAL_CONTROL_DEV_TELEM2', '''Second telemetry port''') +SERIAL_CONTROL_DEV_GPS1 = 2 # First GPS port +enums['SERIAL_CONTROL_DEV'][2] = EnumEntry('SERIAL_CONTROL_DEV_GPS1', '''First GPS port''') +SERIAL_CONTROL_DEV_GPS2 = 3 # Second GPS port +enums['SERIAL_CONTROL_DEV'][3] = EnumEntry('SERIAL_CONTROL_DEV_GPS2', '''Second GPS port''') +SERIAL_CONTROL_DEV_SHELL = 10 # system shell +enums['SERIAL_CONTROL_DEV'][10] = EnumEntry('SERIAL_CONTROL_DEV_SHELL', '''system shell''') +SERIAL_CONTROL_DEV_ENUM_END = 11 # +enums['SERIAL_CONTROL_DEV'][11] = EnumEntry('SERIAL_CONTROL_DEV_ENUM_END', '''''') + +# SERIAL_CONTROL_FLAG +enums['SERIAL_CONTROL_FLAG'] = {} +SERIAL_CONTROL_FLAG_REPLY = 1 # Set if this is a reply +enums['SERIAL_CONTROL_FLAG'][1] = EnumEntry('SERIAL_CONTROL_FLAG_REPLY', '''Set if this is a reply''') +SERIAL_CONTROL_FLAG_RESPOND = 2 # Set if the sender wants the receiver to send a response as another + # SERIAL_CONTROL message +enums['SERIAL_CONTROL_FLAG'][2] = EnumEntry('SERIAL_CONTROL_FLAG_RESPOND', '''Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message''') +SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 # Set if access to the serial port should be removed from whatever + # driver is currently using it, giving + # exclusive access to the SERIAL_CONTROL + # protocol. The port can be handed back by + # sending a request without this flag set +enums['SERIAL_CONTROL_FLAG'][4] = EnumEntry('SERIAL_CONTROL_FLAG_EXCLUSIVE', '''Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set''') +SERIAL_CONTROL_FLAG_BLOCKING = 8 # Block on writes to the serial port +enums['SERIAL_CONTROL_FLAG'][8] = EnumEntry('SERIAL_CONTROL_FLAG_BLOCKING', '''Block on writes to the serial port''') +SERIAL_CONTROL_FLAG_MULTI = 16 # Send multiple replies until port is drained +enums['SERIAL_CONTROL_FLAG'][16] = EnumEntry('SERIAL_CONTROL_FLAG_MULTI', '''Send multiple replies until port is drained''') +SERIAL_CONTROL_FLAG_ENUM_END = 17 # +enums['SERIAL_CONTROL_FLAG'][17] = EnumEntry('SERIAL_CONTROL_FLAG_ENUM_END', '''''') + +# MAV_DISTANCE_SENSOR +enums['MAV_DISTANCE_SENSOR'] = {} +MAV_DISTANCE_SENSOR_LASER = 0 # Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units +enums['MAV_DISTANCE_SENSOR'][0] = EnumEntry('MAV_DISTANCE_SENSOR_LASER', '''Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units''') +MAV_DISTANCE_SENSOR_ULTRASOUND = 1 # Ultrasound rangefinder, e.g. MaxBotix units +enums['MAV_DISTANCE_SENSOR'][1] = EnumEntry('MAV_DISTANCE_SENSOR_ULTRASOUND', '''Ultrasound rangefinder, e.g. MaxBotix units''') +MAV_DISTANCE_SENSOR_INFRARED = 2 # Infrared rangefinder, e.g. Sharp units +enums['MAV_DISTANCE_SENSOR'][2] = EnumEntry('MAV_DISTANCE_SENSOR_INFRARED', '''Infrared rangefinder, e.g. Sharp units''') +MAV_DISTANCE_SENSOR_ENUM_END = 3 # +enums['MAV_DISTANCE_SENSOR'][3] = EnumEntry('MAV_DISTANCE_SENSOR_ENUM_END', '''''') + +# MAV_SENSOR_ORIENTATION +enums['MAV_SENSOR_ORIENTATION'] = {} +MAV_SENSOR_ROTATION_NONE = 0 # Roll: 0, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][0] = EnumEntry('MAV_SENSOR_ROTATION_NONE', '''Roll: 0, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_YAW_45 = 1 # Roll: 0, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][1] = EnumEntry('MAV_SENSOR_ROTATION_YAW_45', '''Roll: 0, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_YAW_90 = 2 # Roll: 0, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][2] = EnumEntry('MAV_SENSOR_ROTATION_YAW_90', '''Roll: 0, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_YAW_135 = 3 # Roll: 0, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][3] = EnumEntry('MAV_SENSOR_ROTATION_YAW_135', '''Roll: 0, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_YAW_180 = 4 # Roll: 0, Pitch: 0, Yaw: 180 +enums['MAV_SENSOR_ORIENTATION'][4] = EnumEntry('MAV_SENSOR_ROTATION_YAW_180', '''Roll: 0, Pitch: 0, Yaw: 180''') +MAV_SENSOR_ROTATION_YAW_225 = 5 # Roll: 0, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][5] = EnumEntry('MAV_SENSOR_ROTATION_YAW_225', '''Roll: 0, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_YAW_270 = 6 # Roll: 0, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][6] = EnumEntry('MAV_SENSOR_ROTATION_YAW_270', '''Roll: 0, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_YAW_315 = 7 # Roll: 0, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][7] = EnumEntry('MAV_SENSOR_ROTATION_YAW_315', '''Roll: 0, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_180 = 8 # Roll: 180, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][8] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180', '''Roll: 180, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9 # Roll: 180, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][9] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_45', '''Roll: 180, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10 # Roll: 180, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][10] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_90', '''Roll: 180, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11 # Roll: 180, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][11] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_135', '''Roll: 180, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_180 = 12 # Roll: 0, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][12] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180', '''Roll: 0, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13 # Roll: 180, Pitch: 0, Yaw: 225 +enums['MAV_SENSOR_ORIENTATION'][13] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_225', '''Roll: 180, Pitch: 0, Yaw: 225''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14 # Roll: 180, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][14] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_270', '''Roll: 180, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15 # Roll: 180, Pitch: 0, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][15] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_YAW_315', '''Roll: 180, Pitch: 0, Yaw: 315''') +MAV_SENSOR_ROTATION_ROLL_90 = 16 # Roll: 90, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][16] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90', '''Roll: 90, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17 # Roll: 90, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][17] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_45', '''Roll: 90, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18 # Roll: 90, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][18] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_90', '''Roll: 90, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19 # Roll: 90, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][19] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_135', '''Roll: 90, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_ROLL_270 = 20 # Roll: 270, Pitch: 0, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][20] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270', '''Roll: 270, Pitch: 0, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21 # Roll: 270, Pitch: 0, Yaw: 45 +enums['MAV_SENSOR_ORIENTATION'][21] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_45', '''Roll: 270, Pitch: 0, Yaw: 45''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22 # Roll: 270, Pitch: 0, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][22] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_90', '''Roll: 270, Pitch: 0, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23 # Roll: 270, Pitch: 0, Yaw: 135 +enums['MAV_SENSOR_ORIENTATION'][23] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_YAW_135', '''Roll: 270, Pitch: 0, Yaw: 135''') +MAV_SENSOR_ROTATION_PITCH_90 = 24 # Roll: 0, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][24] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_90', '''Roll: 0, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_270 = 25 # Roll: 0, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][25] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_270', '''Roll: 0, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26 # Roll: 0, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][26] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_90', '''Roll: 0, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27 # Roll: 0, Pitch: 180, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][27] = EnumEntry('MAV_SENSOR_ROTATION_PITCH_180_YAW_270', '''Roll: 0, Pitch: 180, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28 # Roll: 90, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][28] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_90', '''Roll: 90, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29 # Roll: 180, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][29] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_90', '''Roll: 180, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30 # Roll: 270, Pitch: 90, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][30] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_90', '''Roll: 270, Pitch: 90, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31 # Roll: 90, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][31] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180', '''Roll: 90, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32 # Roll: 270, Pitch: 180, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][32] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_180', '''Roll: 270, Pitch: 180, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33 # Roll: 90, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][33] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_270', '''Roll: 90, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34 # Roll: 180, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][34] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_180_PITCH_270', '''Roll: 180, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35 # Roll: 270, Pitch: 270, Yaw: 0 +enums['MAV_SENSOR_ORIENTATION'][35] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_270_PITCH_270', '''Roll: 270, Pitch: 270, Yaw: 0''') +MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36 # Roll: 90, Pitch: 180, Yaw: 90 +enums['MAV_SENSOR_ORIENTATION'][36] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90', '''Roll: 90, Pitch: 180, Yaw: 90''') +MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37 # Roll: 90, Pitch: 0, Yaw: 270 +enums['MAV_SENSOR_ORIENTATION'][37] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_90_YAW_270', '''Roll: 90, Pitch: 0, Yaw: 270''') +MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 # Roll: 315, Pitch: 315, Yaw: 315 +enums['MAV_SENSOR_ORIENTATION'][38] = EnumEntry('MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315', '''Roll: 315, Pitch: 315, Yaw: 315''') +MAV_SENSOR_ORIENTATION_ENUM_END = 39 # +enums['MAV_SENSOR_ORIENTATION'][39] = EnumEntry('MAV_SENSOR_ORIENTATION_ENUM_END', '''''') + +# MAV_PROTOCOL_CAPABILITY +enums['MAV_PROTOCOL_CAPABILITY'] = {} +MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 # Autopilot supports MISSION float message type. +enums['MAV_PROTOCOL_CAPABILITY'][1] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT', '''Autopilot supports MISSION float message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 # Autopilot supports the new param float message type. +enums['MAV_PROTOCOL_CAPABILITY'][2] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT', '''Autopilot supports the new param float message type.''') +MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 # Autopilot supports MISSION_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][4] = EnumEntry('MAV_PROTOCOL_CAPABILITY_MISSION_INT', '''Autopilot supports MISSION_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 # Autopilot supports COMMAND_INT scaled integer message type. +enums['MAV_PROTOCOL_CAPABILITY'][8] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMMAND_INT', '''Autopilot supports COMMAND_INT scaled integer message type.''') +MAV_PROTOCOL_CAPABILITY_PARAM_UNION = 16 # Autopilot supports the new param union message type. +enums['MAV_PROTOCOL_CAPABILITY'][16] = EnumEntry('MAV_PROTOCOL_CAPABILITY_PARAM_UNION', '''Autopilot supports the new param union message type.''') +MAV_PROTOCOL_CAPABILITY_FTP = 32 # Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. +enums['MAV_PROTOCOL_CAPABILITY'][32] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FTP', '''Autopilot supports the new FILE_TRANSFER_PROTOCOL message type.''') +MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 # Autopilot supports commanding attitude offboard. +enums['MAV_PROTOCOL_CAPABILITY'][64] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET', '''Autopilot supports commanding attitude offboard.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 # Autopilot supports commanding position and velocity targets in local + # NED frame. +enums['MAV_PROTOCOL_CAPABILITY'][128] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED', '''Autopilot supports commanding position and velocity targets in local NED frame.''') +MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 # Autopilot supports commanding position and velocity targets in global + # scaled integers. +enums['MAV_PROTOCOL_CAPABILITY'][256] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT', '''Autopilot supports commanding position and velocity targets in global scaled integers.''') +MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 # Autopilot supports terrain protocol / data handling. +enums['MAV_PROTOCOL_CAPABILITY'][512] = EnumEntry('MAV_PROTOCOL_CAPABILITY_TERRAIN', '''Autopilot supports terrain protocol / data handling.''') +MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 # Autopilot supports direct actuator control. +enums['MAV_PROTOCOL_CAPABILITY'][1024] = EnumEntry('MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET', '''Autopilot supports direct actuator control.''') +MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 # Autopilot supports the flight termination command. +enums['MAV_PROTOCOL_CAPABILITY'][2048] = EnumEntry('MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION', '''Autopilot supports the flight termination command.''') +MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 # Autopilot supports onboard compass calibration. +enums['MAV_PROTOCOL_CAPABILITY'][4096] = EnumEntry('MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION', '''Autopilot supports onboard compass calibration.''') +MAV_PROTOCOL_CAPABILITY_ENUM_END = 4097 # +enums['MAV_PROTOCOL_CAPABILITY'][4097] = EnumEntry('MAV_PROTOCOL_CAPABILITY_ENUM_END', '''''') + +# MAV_ESTIMATOR_TYPE +enums['MAV_ESTIMATOR_TYPE'] = {} +MAV_ESTIMATOR_TYPE_NAIVE = 1 # This is a naive estimator without any real covariance feedback. +enums['MAV_ESTIMATOR_TYPE'][1] = EnumEntry('MAV_ESTIMATOR_TYPE_NAIVE', '''This is a naive estimator without any real covariance feedback.''') +MAV_ESTIMATOR_TYPE_VISION = 2 # Computer vision based estimate. Might be up to scale. +enums['MAV_ESTIMATOR_TYPE'][2] = EnumEntry('MAV_ESTIMATOR_TYPE_VISION', '''Computer vision based estimate. Might be up to scale.''') +MAV_ESTIMATOR_TYPE_VIO = 3 # Visual-inertial estimate. +enums['MAV_ESTIMATOR_TYPE'][3] = EnumEntry('MAV_ESTIMATOR_TYPE_VIO', '''Visual-inertial estimate.''') +MAV_ESTIMATOR_TYPE_GPS = 4 # Plain GPS estimate. +enums['MAV_ESTIMATOR_TYPE'][4] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS', '''Plain GPS estimate.''') +MAV_ESTIMATOR_TYPE_GPS_INS = 5 # Estimator integrating GPS and inertial sensing. +enums['MAV_ESTIMATOR_TYPE'][5] = EnumEntry('MAV_ESTIMATOR_TYPE_GPS_INS', '''Estimator integrating GPS and inertial sensing.''') +MAV_ESTIMATOR_TYPE_ENUM_END = 6 # +enums['MAV_ESTIMATOR_TYPE'][6] = EnumEntry('MAV_ESTIMATOR_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_TYPE +enums['MAV_BATTERY_TYPE'] = {} +MAV_BATTERY_TYPE_UNKNOWN = 0 # Not specified. +enums['MAV_BATTERY_TYPE'][0] = EnumEntry('MAV_BATTERY_TYPE_UNKNOWN', '''Not specified.''') +MAV_BATTERY_TYPE_LIPO = 1 # Lithium polymer battery +enums['MAV_BATTERY_TYPE'][1] = EnumEntry('MAV_BATTERY_TYPE_LIPO', '''Lithium polymer battery''') +MAV_BATTERY_TYPE_LIFE = 2 # Lithium-iron-phosphate battery +enums['MAV_BATTERY_TYPE'][2] = EnumEntry('MAV_BATTERY_TYPE_LIFE', '''Lithium-iron-phosphate battery''') +MAV_BATTERY_TYPE_LION = 3 # Lithium-ION battery +enums['MAV_BATTERY_TYPE'][3] = EnumEntry('MAV_BATTERY_TYPE_LION', '''Lithium-ION battery''') +MAV_BATTERY_TYPE_NIMH = 4 # Nickel metal hydride battery +enums['MAV_BATTERY_TYPE'][4] = EnumEntry('MAV_BATTERY_TYPE_NIMH', '''Nickel metal hydride battery''') +MAV_BATTERY_TYPE_ENUM_END = 5 # +enums['MAV_BATTERY_TYPE'][5] = EnumEntry('MAV_BATTERY_TYPE_ENUM_END', '''''') + +# MAV_BATTERY_FUNCTION +enums['MAV_BATTERY_FUNCTION'] = {} +MAV_BATTERY_FUNCTION_UNKNOWN = 0 # Battery function is unknown +enums['MAV_BATTERY_FUNCTION'][0] = EnumEntry('MAV_BATTERY_FUNCTION_UNKNOWN', '''Battery function is unknown''') +MAV_BATTERY_FUNCTION_ALL = 1 # Battery supports all flight systems +enums['MAV_BATTERY_FUNCTION'][1] = EnumEntry('MAV_BATTERY_FUNCTION_ALL', '''Battery supports all flight systems''') +MAV_BATTERY_FUNCTION_PROPULSION = 2 # Battery for the propulsion system +enums['MAV_BATTERY_FUNCTION'][2] = EnumEntry('MAV_BATTERY_FUNCTION_PROPULSION', '''Battery for the propulsion system''') +MAV_BATTERY_FUNCTION_AVIONICS = 3 # Avionics battery +enums['MAV_BATTERY_FUNCTION'][3] = EnumEntry('MAV_BATTERY_FUNCTION_AVIONICS', '''Avionics battery''') +MAV_BATTERY_TYPE_PAYLOAD = 4 # Payload battery +enums['MAV_BATTERY_FUNCTION'][4] = EnumEntry('MAV_BATTERY_TYPE_PAYLOAD', '''Payload battery''') +MAV_BATTERY_FUNCTION_ENUM_END = 5 # +enums['MAV_BATTERY_FUNCTION'][5] = EnumEntry('MAV_BATTERY_FUNCTION_ENUM_END', '''''') + +# MAV_VTOL_STATE +enums['MAV_VTOL_STATE'] = {} +MAV_VTOL_STATE_UNDEFINED = 0 # MAV is not configured as VTOL +enums['MAV_VTOL_STATE'][0] = EnumEntry('MAV_VTOL_STATE_UNDEFINED', '''MAV is not configured as VTOL''') +MAV_VTOL_STATE_TRANSITION_TO_FW = 1 # VTOL is in transition from multicopter to fixed-wing +enums['MAV_VTOL_STATE'][1] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_FW', '''VTOL is in transition from multicopter to fixed-wing''') +MAV_VTOL_STATE_TRANSITION_TO_MC = 2 # VTOL is in transition from fixed-wing to multicopter +enums['MAV_VTOL_STATE'][2] = EnumEntry('MAV_VTOL_STATE_TRANSITION_TO_MC', '''VTOL is in transition from fixed-wing to multicopter''') +MAV_VTOL_STATE_MC = 3 # VTOL is in multicopter state +enums['MAV_VTOL_STATE'][3] = EnumEntry('MAV_VTOL_STATE_MC', '''VTOL is in multicopter state''') +MAV_VTOL_STATE_FW = 4 # VTOL is in fixed-wing state +enums['MAV_VTOL_STATE'][4] = EnumEntry('MAV_VTOL_STATE_FW', '''VTOL is in fixed-wing state''') +MAV_VTOL_STATE_ENUM_END = 5 # +enums['MAV_VTOL_STATE'][5] = EnumEntry('MAV_VTOL_STATE_ENUM_END', '''''') + +# MAV_LANDED_STATE +enums['MAV_LANDED_STATE'] = {} +MAV_LANDED_STATE_UNDEFINED = 0 # MAV landed state is unknown +enums['MAV_LANDED_STATE'][0] = EnumEntry('MAV_LANDED_STATE_UNDEFINED', '''MAV landed state is unknown''') +MAV_LANDED_STATE_ON_GROUND = 1 # MAV is landed (on ground) +enums['MAV_LANDED_STATE'][1] = EnumEntry('MAV_LANDED_STATE_ON_GROUND', '''MAV is landed (on ground)''') +MAV_LANDED_STATE_IN_AIR = 2 # MAV is in air +enums['MAV_LANDED_STATE'][2] = EnumEntry('MAV_LANDED_STATE_IN_AIR', '''MAV is in air''') +MAV_LANDED_STATE_ENUM_END = 3 # +enums['MAV_LANDED_STATE'][3] = EnumEntry('MAV_LANDED_STATE_ENUM_END', '''''') + +# ADSB_ALTITUDE_TYPE +enums['ADSB_ALTITUDE_TYPE'] = {} +ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 # Altitude reported from a Baro source using QNH reference +enums['ADSB_ALTITUDE_TYPE'][0] = EnumEntry('ADSB_ALTITUDE_TYPE_PRESSURE_QNH', '''Altitude reported from a Baro source using QNH reference''') +ADSB_ALTITUDE_TYPE_GEOMETRIC = 1 # Altitude reported from a GNSS source +enums['ADSB_ALTITUDE_TYPE'][1] = EnumEntry('ADSB_ALTITUDE_TYPE_GEOMETRIC', '''Altitude reported from a GNSS source''') +ADSB_ALTITUDE_TYPE_ENUM_END = 2 # +enums['ADSB_ALTITUDE_TYPE'][2] = EnumEntry('ADSB_ALTITUDE_TYPE_ENUM_END', '''''') + +# ADSB_EMITTER_TYPE +enums['ADSB_EMITTER_TYPE'] = {} +ADSB_EMITTER_TYPE_NO_INFO = 0 # +enums['ADSB_EMITTER_TYPE'][0] = EnumEntry('ADSB_EMITTER_TYPE_NO_INFO', '''''') +ADSB_EMITTER_TYPE_LIGHT = 1 # +enums['ADSB_EMITTER_TYPE'][1] = EnumEntry('ADSB_EMITTER_TYPE_LIGHT', '''''') +ADSB_EMITTER_TYPE_SMALL = 2 # +enums['ADSB_EMITTER_TYPE'][2] = EnumEntry('ADSB_EMITTER_TYPE_SMALL', '''''') +ADSB_EMITTER_TYPE_LARGE = 3 # +enums['ADSB_EMITTER_TYPE'][3] = EnumEntry('ADSB_EMITTER_TYPE_LARGE', '''''') +ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4 # +enums['ADSB_EMITTER_TYPE'][4] = EnumEntry('ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE', '''''') +ADSB_EMITTER_TYPE_HEAVY = 5 # +enums['ADSB_EMITTER_TYPE'][5] = EnumEntry('ADSB_EMITTER_TYPE_HEAVY', '''''') +ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6 # +enums['ADSB_EMITTER_TYPE'][6] = EnumEntry('ADSB_EMITTER_TYPE_HIGHLY_MANUV', '''''') +ADSB_EMITTER_TYPE_ROTOCRAFT = 7 # +enums['ADSB_EMITTER_TYPE'][7] = EnumEntry('ADSB_EMITTER_TYPE_ROTOCRAFT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED = 8 # +enums['ADSB_EMITTER_TYPE'][8] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED', '''''') +ADSB_EMITTER_TYPE_GLIDER = 9 # +enums['ADSB_EMITTER_TYPE'][9] = EnumEntry('ADSB_EMITTER_TYPE_GLIDER', '''''') +ADSB_EMITTER_TYPE_LIGHTER_AIR = 10 # +enums['ADSB_EMITTER_TYPE'][10] = EnumEntry('ADSB_EMITTER_TYPE_LIGHTER_AIR', '''''') +ADSB_EMITTER_TYPE_PARACHUTE = 11 # +enums['ADSB_EMITTER_TYPE'][11] = EnumEntry('ADSB_EMITTER_TYPE_PARACHUTE', '''''') +ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12 # +enums['ADSB_EMITTER_TYPE'][12] = EnumEntry('ADSB_EMITTER_TYPE_ULTRA_LIGHT', '''''') +ADSB_EMITTER_TYPE_UNASSIGNED2 = 13 # +enums['ADSB_EMITTER_TYPE'][13] = EnumEntry('ADSB_EMITTER_TYPE_UNASSIGNED2', '''''') +ADSB_EMITTER_TYPE_UAV = 14 # +enums['ADSB_EMITTER_TYPE'][14] = EnumEntry('ADSB_EMITTER_TYPE_UAV', '''''') +ADSB_EMITTER_TYPE_SPACE = 15 # +enums['ADSB_EMITTER_TYPE'][15] = EnumEntry('ADSB_EMITTER_TYPE_SPACE', '''''') +ADSB_EMITTER_TYPE_UNASSGINED3 = 16 # +enums['ADSB_EMITTER_TYPE'][16] = EnumEntry('ADSB_EMITTER_TYPE_UNASSGINED3', '''''') +ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 # +enums['ADSB_EMITTER_TYPE'][17] = EnumEntry('ADSB_EMITTER_TYPE_EMERGENCY_SURFACE', '''''') +ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18 # +enums['ADSB_EMITTER_TYPE'][18] = EnumEntry('ADSB_EMITTER_TYPE_SERVICE_SURFACE', '''''') +ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19 # +enums['ADSB_EMITTER_TYPE'][19] = EnumEntry('ADSB_EMITTER_TYPE_POINT_OBSTACLE', '''''') +ADSB_EMITTER_TYPE_ENUM_END = 20 # +enums['ADSB_EMITTER_TYPE'][20] = EnumEntry('ADSB_EMITTER_TYPE_ENUM_END', '''''') + +# ADSB_FLAGS +enums['ADSB_FLAGS'] = {} +ADSB_FLAGS_VALID_COORDS = 1 # +enums['ADSB_FLAGS'][1] = EnumEntry('ADSB_FLAGS_VALID_COORDS', '''''') +ADSB_FLAGS_VALID_ALTITUDE = 2 # +enums['ADSB_FLAGS'][2] = EnumEntry('ADSB_FLAGS_VALID_ALTITUDE', '''''') +ADSB_FLAGS_VALID_HEADING = 4 # +enums['ADSB_FLAGS'][4] = EnumEntry('ADSB_FLAGS_VALID_HEADING', '''''') +ADSB_FLAGS_VALID_VELOCITY = 8 # +enums['ADSB_FLAGS'][8] = EnumEntry('ADSB_FLAGS_VALID_VELOCITY', '''''') +ADSB_FLAGS_VALID_CALLSIGN = 16 # +enums['ADSB_FLAGS'][16] = EnumEntry('ADSB_FLAGS_VALID_CALLSIGN', '''''') +ADSB_FLAGS_VALID_SQUAWK = 32 # +enums['ADSB_FLAGS'][32] = EnumEntry('ADSB_FLAGS_VALID_SQUAWK', '''''') +ADSB_FLAGS_SIMULATED = 64 # +enums['ADSB_FLAGS'][64] = EnumEntry('ADSB_FLAGS_SIMULATED', '''''') +ADSB_FLAGS_ENUM_END = 65 # +enums['ADSB_FLAGS'][65] = EnumEntry('ADSB_FLAGS_ENUM_END', '''''') + +# message IDs +MAVLINK_MSG_ID_BAD_DATA = -1 +MAVLINK_MSG_ID_NAV_FILTER_BIAS = 220 +MAVLINK_MSG_ID_RADIO_CALIBRATION = 221 +MAVLINK_MSG_ID_UALBERTA_SYS_STATUS = 222 +MAVLINK_MSG_ID_HEARTBEAT = 0 +MAVLINK_MSG_ID_SYS_STATUS = 1 +MAVLINK_MSG_ID_SYSTEM_TIME = 2 +MAVLINK_MSG_ID_PING = 4 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5 +MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6 +MAVLINK_MSG_ID_AUTH_KEY = 7 +MAVLINK_MSG_ID_SET_MODE = 11 +MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20 +MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21 +MAVLINK_MSG_ID_PARAM_VALUE = 22 +MAVLINK_MSG_ID_PARAM_SET = 23 +MAVLINK_MSG_ID_GPS_RAW_INT = 24 +MAVLINK_MSG_ID_GPS_STATUS = 25 +MAVLINK_MSG_ID_SCALED_IMU = 26 +MAVLINK_MSG_ID_RAW_IMU = 27 +MAVLINK_MSG_ID_RAW_PRESSURE = 28 +MAVLINK_MSG_ID_SCALED_PRESSURE = 29 +MAVLINK_MSG_ID_ATTITUDE = 30 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31 +MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33 +MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34 +MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35 +MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36 +MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37 +MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38 +MAVLINK_MSG_ID_MISSION_ITEM = 39 +MAVLINK_MSG_ID_MISSION_REQUEST = 40 +MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41 +MAVLINK_MSG_ID_MISSION_CURRENT = 42 +MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43 +MAVLINK_MSG_ID_MISSION_COUNT = 44 +MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45 +MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46 +MAVLINK_MSG_ID_MISSION_ACK = 47 +MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48 +MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49 +MAVLINK_MSG_ID_PARAM_MAP_RC = 50 +MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54 +MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55 +MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV = 61 +MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62 +MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV = 63 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV = 64 +MAVLINK_MSG_ID_RC_CHANNELS = 65 +MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66 +MAVLINK_MSG_ID_DATA_STREAM = 67 +MAVLINK_MSG_ID_MANUAL_CONTROL = 69 +MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70 +MAVLINK_MSG_ID_MISSION_ITEM_INT = 73 +MAVLINK_MSG_ID_VFR_HUD = 74 +MAVLINK_MSG_ID_COMMAND_INT = 75 +MAVLINK_MSG_ID_COMMAND_LONG = 76 +MAVLINK_MSG_ID_COMMAND_ACK = 77 +MAVLINK_MSG_ID_MANUAL_SETPOINT = 81 +MAVLINK_MSG_ID_SET_ATTITUDE_TARGET = 82 +MAVLINK_MSG_ID_ATTITUDE_TARGET = 83 +MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED = 84 +MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED = 85 +MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT = 86 +MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT = 87 +MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89 +MAVLINK_MSG_ID_HIL_STATE = 90 +MAVLINK_MSG_ID_HIL_CONTROLS = 91 +MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92 +MAVLINK_MSG_ID_OPTICAL_FLOW = 100 +MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101 +MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102 +MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103 +MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104 +MAVLINK_MSG_ID_HIGHRES_IMU = 105 +MAVLINK_MSG_ID_OPTICAL_FLOW_RAD = 106 +MAVLINK_MSG_ID_HIL_SENSOR = 107 +MAVLINK_MSG_ID_SIM_STATE = 108 +MAVLINK_MSG_ID_RADIO_STATUS = 109 +MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL = 110 +MAVLINK_MSG_ID_TIMESYNC = 111 +MAVLINK_MSG_ID_CAMERA_TRIGGER = 112 +MAVLINK_MSG_ID_HIL_GPS = 113 +MAVLINK_MSG_ID_HIL_OPTICAL_FLOW = 114 +MAVLINK_MSG_ID_HIL_STATE_QUATERNION = 115 +MAVLINK_MSG_ID_SCALED_IMU2 = 116 +MAVLINK_MSG_ID_LOG_REQUEST_LIST = 117 +MAVLINK_MSG_ID_LOG_ENTRY = 118 +MAVLINK_MSG_ID_LOG_REQUEST_DATA = 119 +MAVLINK_MSG_ID_LOG_DATA = 120 +MAVLINK_MSG_ID_LOG_ERASE = 121 +MAVLINK_MSG_ID_LOG_REQUEST_END = 122 +MAVLINK_MSG_ID_GPS_INJECT_DATA = 123 +MAVLINK_MSG_ID_GPS2_RAW = 124 +MAVLINK_MSG_ID_POWER_STATUS = 125 +MAVLINK_MSG_ID_SERIAL_CONTROL = 126 +MAVLINK_MSG_ID_GPS_RTK = 127 +MAVLINK_MSG_ID_GPS2_RTK = 128 +MAVLINK_MSG_ID_SCALED_IMU3 = 129 +MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE = 130 +MAVLINK_MSG_ID_ENCAPSULATED_DATA = 131 +MAVLINK_MSG_ID_DISTANCE_SENSOR = 132 +MAVLINK_MSG_ID_TERRAIN_REQUEST = 133 +MAVLINK_MSG_ID_TERRAIN_DATA = 134 +MAVLINK_MSG_ID_TERRAIN_CHECK = 135 +MAVLINK_MSG_ID_TERRAIN_REPORT = 136 +MAVLINK_MSG_ID_SCALED_PRESSURE2 = 137 +MAVLINK_MSG_ID_ATT_POS_MOCAP = 138 +MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET = 139 +MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET = 140 +MAVLINK_MSG_ID_ALTITUDE = 141 +MAVLINK_MSG_ID_RESOURCE_REQUEST = 142 +MAVLINK_MSG_ID_SCALED_PRESSURE3 = 143 +MAVLINK_MSG_ID_FOLLOW_TARGET = 144 +MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE = 146 +MAVLINK_MSG_ID_BATTERY_STATUS = 147 +MAVLINK_MSG_ID_AUTOPILOT_VERSION = 148 +MAVLINK_MSG_ID_LANDING_TARGET = 149 +MAVLINK_MSG_ID_VIBRATION = 241 +MAVLINK_MSG_ID_HOME_POSITION = 242 +MAVLINK_MSG_ID_SET_HOME_POSITION = 243 +MAVLINK_MSG_ID_MESSAGE_INTERVAL = 244 +MAVLINK_MSG_ID_EXTENDED_SYS_STATE = 245 +MAVLINK_MSG_ID_ADSB_VEHICLE = 246 +MAVLINK_MSG_ID_V2_EXTENSION = 248 +MAVLINK_MSG_ID_MEMORY_VECT = 249 +MAVLINK_MSG_ID_DEBUG_VECT = 250 +MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251 +MAVLINK_MSG_ID_NAMED_VALUE_INT = 252 +MAVLINK_MSG_ID_STATUSTEXT = 253 +MAVLINK_MSG_ID_DEBUG = 254 + +class MAVLink_nav_filter_bias_message(MAVLink_message): + ''' + Accelerometer and Gyro biases from the navigation filter + ''' + id = MAVLINK_MSG_ID_NAV_FILTER_BIAS + name = 'NAV_FILTER_BIAS' + fieldnames = ['usec', 'accel_0', 'accel_1', 'accel_2', 'gyro_0', 'gyro_1', 'gyro_2'] + ordered_fieldnames = [ 'usec', 'accel_0', 'accel_1', 'accel_2', 'gyro_0', 'gyro_1', 'gyro_2' ] + format = ' + value[float]. This allows to send a parameter to any other + component (such as the GCS) without the need of previous + knowledge of possible parameter names. Thus the same GCS can + store different parameters for different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a full + documentation of QGroundControl and IMU code. + ''' + id = MAVLINK_MSG_ID_PARAM_REQUEST_READ + name = 'PARAM_REQUEST_READ' + fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] + ordered_fieldnames = [ 'param_index', 'target_system', 'target_component', 'param_id' ] + format = '= 1 and self.buf[0] != 254: + magic = self.buf[0] + self.buf = self.buf[1:] + if self.robust_parsing: + m = MAVLink_bad_data(chr(magic), "Bad prefix") + self.expected_length = 8 + self.total_receive_errors += 1 + return m + if self.have_prefix_error: + return None + self.have_prefix_error = True + self.total_receive_errors += 1 + raise MAVError("invalid MAVLink prefix '%s'" % magic) + self.have_prefix_error = False + if len(self.buf) >= 2: + if sys.version_info[0] < 3: + (magic, self.expected_length) = struct.unpack('BB', str(self.buf[0:2])) # bytearrays are not supported in py 2.7.3 + else: + (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) + self.expected_length += 8 + if self.expected_length >= 8 and len(self.buf) >= self.expected_length: + mbuf = array.array('B', self.buf[0:self.expected_length]) + self.buf = self.buf[self.expected_length:] + self.expected_length = 8 + if self.robust_parsing: + try: + m = self.decode(mbuf) + except MAVError as reason: + m = MAVLink_bad_data(mbuf, reason.message) + self.total_receive_errors += 1 + else: + m = self.decode(mbuf) + return m + return None + + def parse_buffer(self, s): + '''input some data bytes, possibly returning a list of new messages''' + m = self.parse_char(s) + if m is None: + return None + ret = [m] + while True: + m = self.parse_char("") + if m is None: + return ret + ret.append(m) + return ret + + def decode(self, msgbuf): + '''decode a buffer as a MAVLink message''' + # decode the header + try: + magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) + except struct.error as emsg: + raise MAVError('Unable to unpack MAVLink header: %s' % emsg) + if ord(magic) != 254: + raise MAVError("invalid MAVLink prefix '%s'" % magic) + if mlen != len(msgbuf)-8: + raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) + + if not msgId in mavlink_map: + raise MAVError('unknown MAVLink message ID %u' % msgId) + + # decode the payload + type = mavlink_map[msgId] + fmt = type.format + order_map = type.orders + len_map = type.lengths + crc_extra = type.crc_extra + + # decode the checksum + try: + crc, = struct.unpack(' + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) + + def param_request_read_send(self, target_system, target_component, param_id, param_index): + ''' + Request to read the onboard parameter with the param_id string id. + Onboard parameters are stored as key[const char*] -> + value[float]. This allows to send a parameter to any + other component (such as the GCS) without the need of + previous knowledge of possible parameter names. Thus + the same GCS can store different parameters for + different autopilots. See also + http://qgroundcontrol.org/parameter_interface for a + full documentation of QGroundControl and IMU code. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) (int16_t) + + ''' + return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) + + def param_request_list_encode(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_param_request_list_message(target_system, target_component) + + def param_request_list_send(self, target_system, target_component): + ''' + Request all parameters of this component. After his request, all + parameters are emitted. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.param_request_list_encode(target_system, target_component)) + + def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) + + def param_value_send(self, param_id, param_value, param_type, param_count, param_index): + ''' + Emit the value of a onboard parameter. The inclusion of param_count + and param_index in the message allows the recipient to + keep track of received parameters and allows him to + re-request missing parameters after a loss or timeout. + + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + param_count : Total number of onboard parameters (uint16_t) + param_index : Index of this onboard parameter (uint16_t) + + ''' + return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) + + def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) + + def param_set_send(self, target_system, target_component, param_id, param_value, param_type): + ''' + Set a parameter value TEMPORARILY to RAM. It will be reset to default + on system reboot. Send the ACTION + MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM + contents to EEPROM. IMPORTANT: The receiving component + should acknowledge the new parameter value by sending + a param_value message to all communication partners. + This will also ensure that multiple GCS all have an + up-to-date list of all parameters. If the sending GCS + did not receive a PARAM_VALUE message within its + timeout time, it should re-send the PARAM_SET message. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_value : Onboard parameter value (float) + param_type : Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. (uint8_t) + + ''' + return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) + + def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) + + def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global position + estimate of the system, but rather a RAW sensor value. + See message GLOBAL_POSITION for the global position + estimate. Coordinate frame is right-handed, Z-axis up + (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. (int32_t) + eph : GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) + + def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) + + def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): + ''' + The positioning status, as reported by GPS. This message is intended + to display status information about each satellite + visible to the receiver. See message GLOBAL_POSITION + for the global position estimate. This message can + contain information for up to 20 satellites. + + satellites_visible : Number of satellites visible (uint8_t) + satellite_prn : Global satellite ID (uint8_t) + satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) + satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) + satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) + satellite_snr : Signal to noise ratio of satellite (uint8_t) + + ''' + return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) + + def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for the usual 9DOF sensor setup. This message + should always contain the true raw values without any + scaling to allow data capture and system debugging. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + xacc : X acceleration (raw) (int16_t) + yacc : Y acceleration (raw) (int16_t) + zacc : Z acceleration (raw) (int16_t) + xgyro : Angular speed around X axis (raw) (int16_t) + ygyro : Angular speed around Y axis (raw) (int16_t) + zgyro : Angular speed around Z axis (raw) (int16_t) + xmag : X Magnetic field (raw) (int16_t) + ymag : Y Magnetic field (raw) (int16_t) + zmag : Z Magnetic field (raw) (int16_t) + + ''' + return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) + + def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): + ''' + The RAW pressure readings for the typical setup of one absolute + pressure and one differential pressure sensor. The + sensor values should be the raw, UNSCALED ADC values. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + press_abs : Absolute pressure (raw) (int16_t) + press_diff1 : Differential pressure 1 (raw, 0 if nonexistant) (int16_t) + press_diff2 : Differential pressure 2 (raw, 0 if nonexistant) (int16_t) + temperature : Raw Temperature measurement (raw) (int16_t) + + ''' + return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) + + def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + The pressure readings for the typical setup of one absolute and + differential pressure sensor. The units are as + specified in each field. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) + + def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + roll : Roll angle (rad, -pi..+pi) (float) + pitch : Pitch angle (rad, -pi..+pi) (float) + yaw : Yaw angle (rad, -pi..+pi) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) + + def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) + + def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q1 : Quaternion component 1, w (1 in null-rotation) (float) + q2 : Quaternion component 2, x (0 in null-rotation) (float) + q3 : Quaternion component 3, y (0 in null-rotation) (float) + q4 : Quaternion component 4, z (0 in null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + + ''' + return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) + + def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) + + def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (float) + vy : Y Speed (float) + vz : Z Speed (float) + + ''' + return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) + + def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) + + def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the + resolution of float is not sufficient. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude, positive north), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude, positive east), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude, positive down), expressed as m/s * 100 (int16_t) + hdg : Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + + ''' + return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) + + def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) + + def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): + ''' + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, + (100%) 10000. Channels that are inactive should be set + to UINT16_MAX. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. (int16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) + + def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) + + def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): + ''' + The RAW values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) + + def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) + + def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): + ''' + The RAW values of the servo outputs (for RC input from the remote, use + the RC_CHANNELS messages). The standard PPM modulation + is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. + + time_usec : Timestamp (microseconds since system boot) (uint32_t) + port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) + servo1_raw : Servo output 1 value, in microseconds (uint16_t) + servo2_raw : Servo output 2 value, in microseconds (uint16_t) + servo3_raw : Servo output 3 value, in microseconds (uint16_t) + servo4_raw : Servo output 4 value, in microseconds (uint16_t) + servo5_raw : Servo output 5 value, in microseconds (uint16_t) + servo6_raw : Servo output 6 value, in microseconds (uint16_t) + servo7_raw : Servo output 7 value, in microseconds (uint16_t) + servo8_raw : Servo output 8 value, in microseconds (uint16_t) + + ''' + return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) + + def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + Request a partial list of mission items from the system/component. + http://qgroundcontrol.org/mavlink/waypoint_protocol. + If start and end index are the same, just send one + waypoint. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default (int16_t) + end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) + + ''' + return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) + + def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): + ''' + This message is sent to the MAV to write a partial list. If start + index == end index, only one item will be transmitted + / updated. If the start index is NOT 0 and above the + current list size, this request should be REJECTED! + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) + end_index : End index, equal or greater than start index. (int16_t) + + ''' + return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) + + def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See also + http://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position, global: latitude (float) + y : PARAM6 / y position: global: longitude (float) + z : PARAM7 / z position: global: altitude (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def mission_request_encode(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_request_message(target_system, target_component, seq) + + def mission_request_send(self, target_system, target_component, seq): + ''' + Request the information of the mission item with the sequence number + seq. The response of the system to this message should + be a MISSION_ITEM message. + http://qgroundcontrol.org/mavlink/waypoint_protocol + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_request_encode(target_system, target_component, seq)) + + def mission_set_current_encode(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_set_current_message(target_system, target_component, seq) + + def mission_set_current_send(self, target_system, target_component, seq): + ''' + Set the mission item with sequence number seq as current item. This + means that the MAV will continue to this mission item + on the shortest path (not following the mission items + in-between). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_set_current_encode(target_system, target_component, seq)) + + def mission_current_encode(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_current_message(seq) + + def mission_current_send(self, seq): + ''' + Message that announces the sequence number of the current active + mission item. The MAV will fly towards this mission + item. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_current_encode(seq)) + + def mission_request_list_encode(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_request_list_message(target_system, target_component) + + def mission_request_list_send(self, target_system, target_component): + ''' + Request the overall list of mission items from the system/component. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_request_list_encode(target_system, target_component)) + + def mission_count_encode(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return MAVLink_mission_count_message(target_system, target_component, count) + + def mission_count_send(self, target_system, target_component, count): + ''' + This message is emitted as response to MISSION_REQUEST_LIST by the MAV + and to initiate a write transaction. The GCS can then + request the individual mission item based on the + knowledge of the total number of MISSIONs. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + count : Number of mission items in the sequence (uint16_t) + + ''' + return self.send(self.mission_count_encode(target_system, target_component, count)) + + def mission_clear_all_encode(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_mission_clear_all_message(target_system, target_component) + + def mission_clear_all_send(self, target_system, target_component): + ''' + Delete all mission items at once. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.mission_clear_all_encode(target_system, target_component)) + + def mission_item_reached_encode(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return MAVLink_mission_item_reached_message(seq) + + def mission_item_reached_send(self, seq): + ''' + A certain mission item has been reached. The system will either hold + this position (or circle on the orbit) or (if the + autocontinue on the WP was set) continue to the next + MISSION. + + seq : Sequence (uint16_t) + + ''' + return self.send(self.mission_item_reached_encode(seq)) + + def mission_ack_encode(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return MAVLink_mission_ack_message(target_system, target_component, type) + + def mission_ack_send(self, target_system, target_component, type): + ''' + Ack message during MISSION handling. The type field states if this + message is a positive ack (type=0) or if an error + happened (type=non-zero). + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type : See MAV_MISSION_RESULT enum (uint8_t) + + ''' + return self.send(self.mission_ack_encode(target_system, target_component, type)) + + def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) + + def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): + ''' + As local waypoints exist, the global MISSION reference allows to + transform between the local coordinate frame and the + global (GPS) coordinate frame. This can be necessary + when e.g. in- and outdoor settings are connected and + the MAV should move from in- to outdoor. + + target_system : System ID (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) + + def gps_global_origin_encode(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return MAVLink_gps_global_origin_message(latitude, longitude, altitude) + + def gps_global_origin_send(self, latitude, longitude, altitude): + ''' + Once the MAV sets a new GPS-Local correspondence, this message + announces the origin (0,0,0) position + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84), in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + + ''' + return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) + + def param_map_rc_encode(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return MAVLink_param_map_rc_message(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max) + + def param_map_rc_send(self, target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max): + ''' + Bind a RC channel to a parameter. The parameter should change accoding + to the RC channel value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + param_id : Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string (char) + param_index : Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. (int16_t) + parameter_rc_channel_index : Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. (uint8_t) + param_value0 : Initial parameter value (float) + scale : Scale, maps the RC range [-1, 1] to a parameter value (float) + param_value_min : Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) (float) + param_value_max : Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) (float) + + ''' + return self.send(self.param_map_rc_encode(target_system, target_component, param_id, param_index, parameter_rc_channel_index, param_value0, scale, param_value_min, param_value_max)) + + def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Set a safety zone (volume), which is defined by two corners of a cube. + This message can be used to tell the MAV which + setpoints/MISSIONs to accept and which to reject. + Safety areas are often enforced by national or + competition regulations. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) + + def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): + ''' + Read out the safety zone the MAV currently assumes. + + frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) + p1x : x position 1 / Latitude 1 (float) + p1y : y position 1 / Longitude 1 (float) + p1z : z position 1 / Altitude 1 (float) + p2x : x position 2 / Latitude 2 (float) + p2y : y position 2 / Longitude 2 (float) + p2z : z position 2 / Altitude 2 (float) + + ''' + return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) + + def attitude_quaternion_cov_encode(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return MAVLink_attitude_quaternion_cov_message(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance) + + def attitude_quaternion_cov_send(self, time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance): + ''' + The attitude in the aeronautical frame (right-handed, Z-down, X-front, + Y-right), expressed as quaternion. Quaternion order is + w, x, y, z and a zero rotation would be expressed as + (1 0 0 0). + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + q : Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) (float) + rollspeed : Roll angular speed (rad/s) (float) + pitchspeed : Pitch angular speed (rad/s) (float) + yawspeed : Yaw angular speed (rad/s) (float) + covariance : Attitude covariance (float) + + ''' + return self.send(self.attitude_quaternion_cov_encode(time_boot_ms, q, rollspeed, pitchspeed, yawspeed, covariance)) + + def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) + + def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): + ''' + Outputs of the APM navigation controller. The primary use of this + message is to check the response and signs of the + controller before actual flight and to assist with + tuning controller parameters. + + nav_roll : Current desired roll in degrees (float) + nav_pitch : Current desired pitch in degrees (float) + nav_bearing : Current desired heading in degrees (int16_t) + target_bearing : Bearing to current MISSION/target in degrees (int16_t) + wp_dist : Distance to active MISSION in meters (uint16_t) + alt_error : Current altitude error in meters (float) + aspd_error : Current airspeed error in meters/second (float) + xtrack_error : Current crosstrack error on x-y plane in meters (float) + + ''' + return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) + + def global_position_int_cov_encode(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return MAVLink_global_position_int_cov_message(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance) + + def global_position_int_cov_send(self, time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance): + ''' + The filtered global position (e.g. fused GPS and accelerometers). The + position is in GPS-frame (right-handed, Z-up). It is + designed as scaled integer message since the + resolution of float is not sufficient. NOTE: This + message is intended for onboard networks / companion + computers and higher-bandwidth links and optimized for + accuracy and completeness. Please use the + GLOBAL_POSITION_INT message for a minimal subset. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) + relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s (float) + vy : Ground Y Speed (Longitude), expressed as m/s (float) + vz : Ground Z Speed (Altitude), expressed as m/s (float) + covariance : Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) (float) + + ''' + return self.send(self.global_position_int_cov_encode(time_boot_ms, time_utc, estimator_type, lat, lon, alt, relative_alt, vx, vy, vz, covariance)) + + def local_position_ned_cov_encode(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return MAVLink_local_position_ned_cov_message(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance) + + def local_position_ned_cov_send(self, time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance): + ''' + The filtered local position (e.g. fused computer vision and + accelerometers). Coordinate frame is right-handed, + Z-axis down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp (uint32_t) + time_utc : Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. (uint64_t) + estimator_type : Class id of the estimator this estimate originated from. (uint8_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + vx : X Speed (m/s) (float) + vy : Y Speed (m/s) (float) + vz : Z Speed (m/s) (float) + ax : X Acceleration (m/s^2) (float) + ay : Y Acceleration (m/s^2) (float) + az : Z Acceleration (m/s^2) (float) + covariance : Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) (float) + + ''' + return self.send(self.local_position_ned_cov_encode(time_boot_ms, time_utc, estimator_type, x, y, z, vx, vy, vz, ax, ay, az, covariance)) + + def rc_channels_encode(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return MAVLink_rc_channels_message(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi) + + def rc_channels_send(self, time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi): + ''' + The PPM values of the RC channels received. The standard PPM + modulation is as follows: 1000 microseconds: 0%, 2000 + microseconds: 100%. Individual receivers/transmitters + might violate this specification. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + chancount : Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan9_raw : RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan10_raw : RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan11_raw : RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan12_raw : RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan13_raw : RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan14_raw : RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan15_raw : RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan16_raw : RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan17_raw : RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + chan18_raw : RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. (uint8_t) + + ''' + return self.send(self.rc_channels_encode(time_boot_ms, chancount, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, chan13_raw, chan14_raw, chan15_raw, chan16_raw, chan17_raw, chan18_raw, rssi)) + + def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) + + def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): + ''' + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + + target_system : The target requested to send the message stream. (uint8_t) + target_component : The target requested to send the message stream. (uint8_t) + req_stream_id : The ID of the requested data stream (uint8_t) + req_message_rate : The requested message rate (uint16_t) + start_stop : 1 to start sending, 0 to stop sending. (uint8_t) + + ''' + return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) + + def data_stream_encode(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return MAVLink_data_stream_message(stream_id, message_rate, on_off) + + def data_stream_send(self, stream_id, message_rate, on_off): + ''' + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + + stream_id : The ID of the requested data stream (uint8_t) + message_rate : The message rate (uint16_t) + on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) + + ''' + return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) + + def manual_control_encode(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return MAVLink_manual_control_message(target, x, y, z, r, buttons) + + def manual_control_send(self, target, x, y, z, r, buttons): + ''' + This message provides an API for manually controlling the vehicle + using standard joystick axes nomenclature, along with + a joystick-like input device. Unused axes can be + disabled an buttons are also transmit as boolean + values of their + + target : The system to be controlled. (uint8_t) + x : X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. (int16_t) + y : Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. (int16_t) + z : Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. (int16_t) + r : R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. (int16_t) + buttons : A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. (uint16_t) + + ''' + return self.send(self.manual_control_encode(target, x, y, z, r, buttons)) + + def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) + + def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): + ''' + The RAW values of the RC channels sent to the MAV to override info + received from the RC radio. A value of UINT16_MAX + means no change to that channel. A value of 0 means + control of that channel should be released back to the + RC radio. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + chan1_raw : RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan2_raw : RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan3_raw : RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan4_raw : RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan5_raw : RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan6_raw : RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan7_raw : RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + chan8_raw : RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. (uint16_t) + + ''' + return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) + + def mission_item_int_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_mission_item_int_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def mission_item_int_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission + item on the system. The mission item can be either in + x, y, z meters (type: LOCAL) or x:lat, y:lon, + z:altitude. Local frame is Z-down, right handed (NED), + global frame is Z-up, right handed (ENU). See alsohttp + ://qgroundcontrol.org/mavlink/waypoint_protocol. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + seq : Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). (uint16_t) + frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.mission_item_int_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) + + def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): + ''' + Metrics typically displayed on a HUD for fixed wing aircraft + + airspeed : Current airspeed in m/s (float) + groundspeed : Current ground speed in m/s (float) + heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) + throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) + alt : Current altitude (MSL), in meters (float) + climb : Current climb rate in meters/second (float) + + ''' + return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) + + def command_int_encode(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return MAVLink_command_int_message(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) + + def command_int_send(self, target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): + ''' + Message encoding a command with parameters as scaled integers. Scaling + depends on the actual command value. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + frame : The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h (uint8_t) + command : The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs (uint16_t) + current : false:0, true:1 (uint8_t) + autocontinue : autocontinue to next wp (uint8_t) + param1 : PARAM1, see MAV_CMD enum (float) + param2 : PARAM2, see MAV_CMD enum (float) + param3 : PARAM3, see MAV_CMD enum (float) + param4 : PARAM4, see MAV_CMD enum (float) + x : PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 (int32_t) + y : PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 (int32_t) + z : PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. (float) + + ''' + return self.send(self.command_int_encode(target_system, target_component, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) + + def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) + + def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): + ''' + Send a command with up to seven parameters to the MAV + + target_system : System which should execute the command (uint8_t) + target_component : Component which should execute the command, 0 for all components (uint8_t) + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) + param1 : Parameter 1, as defined by MAV_CMD enum. (float) + param2 : Parameter 2, as defined by MAV_CMD enum. (float) + param3 : Parameter 3, as defined by MAV_CMD enum. (float) + param4 : Parameter 4, as defined by MAV_CMD enum. (float) + param5 : Parameter 5, as defined by MAV_CMD enum. (float) + param6 : Parameter 6, as defined by MAV_CMD enum. (float) + param7 : Parameter 7, as defined by MAV_CMD enum. (float) + + ''' + return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) + + def command_ack_encode(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return MAVLink_command_ack_message(command, result) + + def command_ack_send(self, command, result): + ''' + Report status of a command. Includes feedback wether the command was + executed. + + command : Command ID, as defined by MAV_CMD enum. (uint16_t) + result : See MAV_RESULT enum (uint8_t) + + ''' + return self.send(self.command_ack_encode(command, result)) + + def manual_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return MAVLink_manual_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch) + + def manual_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch): + ''' + Setpoint in roll, pitch, yaw and thrust from the operator + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + roll : Desired roll rate in radians per second (float) + pitch : Desired pitch rate in radians per second (float) + yaw : Desired yaw rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (float) + mode_switch : Flight mode switch position, 0.. 255 (uint8_t) + manual_override_switch : Override mode switch position, 0.. 255 (uint8_t) + + ''' + return self.send(self.manual_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust, mode_switch, manual_override_switch)) + + def set_attitude_target_encode(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_set_attitude_target_message(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def set_attitude_target_send(self, time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Sets a desired vehicle attitude. Used by an external controller to + command the vehicle (manual controller or other + system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.set_attitude_target_encode(time_boot_ms, target_system, target_component, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def attitude_target_encode(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return MAVLink_attitude_target_message(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust) + + def attitude_target_send(self, time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust): + ''' + Reports the current commanded attitude of the vehicle as specified by + the autopilot. This should match the commands sent in + a SET_ATTITUDE_TARGET message if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + type_mask : Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude (uint8_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + body_roll_rate : Body roll rate in radians per second (float) + body_pitch_rate : Body roll rate in radians per second (float) + body_yaw_rate : Body roll rate in radians per second (float) + thrust : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (float) + + ''' + return self.send(self.attitude_target_encode(time_boot_ms, type_mask, q, body_roll_rate, body_pitch_rate, body_yaw_rate, thrust)) + + def set_position_target_local_ned_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_local_ned_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_local_ned_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position in a local north-east-down coordinate + frame. Used by an external controller to command the + vehicle (manual controller or other system). + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_local_ned_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_local_ned_encode(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_local_ned_message(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_local_ned_send(self, time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_LOCAL_NED if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + x : X Position in NED frame in meters (float) + y : Y Position in NED frame in meters (float) + z : Z Position in NED frame in meters (note, altitude is negative in NED) (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_local_ned_encode(time_boot_ms, coordinate_frame, type_mask, x, y, z, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def set_position_target_global_int_encode(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_set_position_target_global_int_message(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def set_position_target_global_int_send(self, time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Sets a desired vehicle position, velocity, and/or acceleration in a + global coordinate system (WGS84). Used by an external + controller to command the vehicle (manual controller + or other system). + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.set_position_target_global_int_encode(time_boot_ms, target_system, target_component, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def position_target_global_int_encode(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return MAVLink_position_target_global_int_message(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate) + + def position_target_global_int_send(self, time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate): + ''' + Reports the current commanded vehicle position, velocity, and + acceleration as specified by the autopilot. This + should match the commands sent in + SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being + controlled this way. + + time_boot_ms : Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. (uint32_t) + coordinate_frame : Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 (uint8_t) + type_mask : Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate (uint16_t) + lat_int : X Position in WGS84 frame in 1e7 * meters (int32_t) + lon_int : Y Position in WGS84 frame in 1e7 * meters (int32_t) + alt : Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT (float) + vx : X velocity in NED frame in meter / s (float) + vy : Y velocity in NED frame in meter / s (float) + vz : Z velocity in NED frame in meter / s (float) + afx : X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afy : Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + afz : Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N (float) + yaw : yaw setpoint in rad (float) + yaw_rate : yaw rate setpoint in rad/s (float) + + ''' + return self.send(self.position_target_global_int_encode(time_boot_ms, coordinate_frame, type_mask, lat_int, lon_int, alt, vx, vy, vz, afx, afy, afz, yaw, yaw_rate)) + + def local_position_ned_system_global_offset_encode(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return MAVLink_local_position_ned_system_global_offset_message(time_boot_ms, x, y, z, roll, pitch, yaw) + + def local_position_ned_system_global_offset_send(self, time_boot_ms, x, y, z, roll, pitch, yaw): + ''' + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages + of MAV X and the global coordinate frame in NED + coordinates. Coordinate frame is right-handed, Z-axis + down (aeronautical frame, NED / north-east-down + convention) + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + x : X Position (float) + y : Y Position (float) + z : Z Position (float) + roll : Roll (float) + pitch : Pitch (float) + yaw : Yaw (float) + + ''' + return self.send(self.local_position_ned_system_global_offset_encode(time_boot_ms, x, y, z, roll, pitch, yaw)) + + def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) + + def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): + ''' + DEPRECATED PACKET! Suffers from missing airspeed fields and + singularities due to Euler angles. Please use + HIL_STATE_QUATERNION instead. Sent from simulation to + autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll : Roll angle (rad) (float) + pitch : Pitch angle (rad) (float) + yaw : Yaw angle (rad) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) + + def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) + + def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): + ''' + Sent from autopilot to simulation. Hardware in the loop control + outputs + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + roll_ailerons : Control output -1 .. 1 (float) + pitch_elevator : Control output -1 .. 1 (float) + yaw_rudder : Control output -1 .. 1 (float) + throttle : Throttle 0 .. 1 (float) + aux1 : Aux 1, -1 .. 1 (float) + aux2 : Aux 2, -1 .. 1 (float) + aux3 : Aux 3, -1 .. 1 (float) + aux4 : Aux 4, -1 .. 1 (float) + mode : System mode (MAV_MODE) (uint8_t) + nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) + + ''' + return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) + + def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) + + def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): + ''' + Sent from simulation to autopilot. The RAW values of the RC channels + received. The standard PPM modulation is as follows: + 1000 microseconds: 0%, 2000 microseconds: 100%. + Individual receivers/transmitters might violate this + specification. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + chan1_raw : RC channel 1 value, in microseconds (uint16_t) + chan2_raw : RC channel 2 value, in microseconds (uint16_t) + chan3_raw : RC channel 3 value, in microseconds (uint16_t) + chan4_raw : RC channel 4 value, in microseconds (uint16_t) + chan5_raw : RC channel 5 value, in microseconds (uint16_t) + chan6_raw : RC channel 6 value, in microseconds (uint16_t) + chan7_raw : RC channel 7 value, in microseconds (uint16_t) + chan8_raw : RC channel 8 value, in microseconds (uint16_t) + chan9_raw : RC channel 9 value, in microseconds (uint16_t) + chan10_raw : RC channel 10 value, in microseconds (uint16_t) + chan11_raw : RC channel 11 value, in microseconds (uint16_t) + chan12_raw : RC channel 12 value, in microseconds (uint16_t) + rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) + + ''' + return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) + + def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance) + + def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance): + ''' + Optical flow from a flow sensor (e.g. optical mouse sensor) + + time_usec : Timestamp (UNIX) (uint64_t) + sensor_id : Sensor ID (uint8_t) + flow_x : Flow in pixels * 10 in x-sensor direction (dezi-pixels) (int16_t) + flow_y : Flow in pixels * 10 in y-sensor direction (dezi-pixels) (int16_t) + flow_comp_m_x : Flow in meters in x-sensor direction, angular-speed compensated (float) + flow_comp_m_y : Flow in meters in y-sensor direction, angular-speed compensated (float) + quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) + ground_distance : Ground distance in meters. Positive value: distance known. Negative value: Unknown distance (float) + + ''' + return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, flow_comp_m_x, flow_comp_m_y, quality, ground_distance)) + + def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def vision_speed_estimate_encode(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return MAVLink_vision_speed_estimate_message(usec, x, y, z) + + def vision_speed_estimate_send(self, usec, x, y, z): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X speed (float) + y : Global Y speed (float) + z : Global Z speed (float) + + ''' + return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) + + def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) + + def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): + ''' + + + usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + x : Global X position (float) + y : Global Y position (float) + z : Global Z position (float) + roll : Roll angle in rad (float) + pitch : Pitch angle in rad (float) + yaw : Yaw angle in rad (float) + + ''' + return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) + + def highres_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return MAVLink_highres_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def highres_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis (rad / sec) (float) + ygyro : Angular speed around Y axis (rad / sec) (float) + zgyro : Angular speed around Z axis (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature (uint16_t) + + ''' + return self.send(self.highres_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def optical_flow_rad_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_optical_flow_rad_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def optical_flow_rad_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse + sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.optical_flow_rad_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_sensor_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return MAVLink_hil_sensor_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated) + + def hil_sensor_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated): + ''' + The IMU readings in SI units in NED body frame + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + xacc : X acceleration (m/s^2) (float) + yacc : Y acceleration (m/s^2) (float) + zacc : Z acceleration (m/s^2) (float) + xgyro : Angular speed around X axis in body frame (rad / sec) (float) + ygyro : Angular speed around Y axis in body frame (rad / sec) (float) + zgyro : Angular speed around Z axis in body frame (rad / sec) (float) + xmag : X Magnetic field (Gauss) (float) + ymag : Y Magnetic field (Gauss) (float) + zmag : Z Magnetic field (Gauss) (float) + abs_pressure : Absolute pressure in millibar (float) + diff_pressure : Differential pressure (airspeed) in millibar (float) + pressure_alt : Altitude calculated from pressure (float) + temperature : Temperature in degrees celsius (float) + fields_updated : Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. (uint32_t) + + ''' + return self.send(self.hil_sensor_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature, fields_updated)) + + def sim_state_encode(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return MAVLink_sim_state_message(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd) + + def sim_state_send(self, q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd): + ''' + Status of simulation environment, if used + + q1 : True attitude quaternion component 1, w (1 in null-rotation) (float) + q2 : True attitude quaternion component 2, x (0 in null-rotation) (float) + q3 : True attitude quaternion component 3, y (0 in null-rotation) (float) + q4 : True attitude quaternion component 4, z (0 in null-rotation) (float) + roll : Attitude roll expressed as Euler angles, not recommended except for human-readable outputs (float) + pitch : Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs (float) + yaw : Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs (float) + xacc : X acceleration m/s/s (float) + yacc : Y acceleration m/s/s (float) + zacc : Z acceleration m/s/s (float) + xgyro : Angular speed around X axis rad/s (float) + ygyro : Angular speed around Y axis rad/s (float) + zgyro : Angular speed around Z axis rad/s (float) + lat : Latitude in degrees (float) + lon : Longitude in degrees (float) + alt : Altitude in meters (float) + std_dev_horz : Horizontal position standard deviation (float) + std_dev_vert : Vertical position standard deviation (float) + vn : True velocity in m/s in NORTH direction in earth-fixed NED frame (float) + ve : True velocity in m/s in EAST direction in earth-fixed NED frame (float) + vd : True velocity in m/s in DOWN direction in earth-fixed NED frame (float) + + ''' + return self.send(self.sim_state_encode(q1, q2, q3, q4, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro, lat, lon, alt, std_dev_horz, std_dev_vert, vn, ve, vd)) + + def radio_status_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return MAVLink_radio_status_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) + + def radio_status_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): + ''' + Status generated by radio and injected into MAVLink stream. + + rssi : Local signal strength (uint8_t) + remrssi : Remote signal strength (uint8_t) + txbuf : Remaining free buffer space in percent. (uint8_t) + noise : Background noise level (uint8_t) + remnoise : Remote background noise level (uint8_t) + rxerrors : Receive errors (uint16_t) + fixed : Count of error corrected packets (uint16_t) + + ''' + return self.send(self.radio_status_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) + + def file_transfer_protocol_encode(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_file_transfer_protocol_message(target_network, target_system, target_component, payload) + + def file_transfer_protocol_send(self, target_network, target_system, target_component, payload): + ''' + File transfer message + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.file_transfer_protocol_encode(target_network, target_system, target_component, payload)) + + def timesync_encode(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return MAVLink_timesync_message(tc1, ts1) + + def timesync_send(self, tc1, ts1): + ''' + Time synchronization message. + + tc1 : Time sync timestamp 1 (int64_t) + ts1 : Time sync timestamp 2 (int64_t) + + ''' + return self.send(self.timesync_encode(tc1, ts1)) + + def camera_trigger_encode(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return MAVLink_camera_trigger_message(time_usec, seq) + + def camera_trigger_send(self, time_usec, seq): + ''' + Camera-IMU triggering and synchronisation message. + + time_usec : Timestamp for the image frame in microseconds (uint64_t) + seq : Image frame sequence (uint32_t) + + ''' + return self.send(self.camera_trigger_encode(time_usec, seq)) + + def hil_gps_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return MAVLink_hil_gps_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible) + + def hil_gps_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible): + ''' + The global position, as returned by the Global Positioning System + (GPS). This is NOT the global + position estimate of the sytem, but rather a RAW + sensor value. See message GLOBAL_POSITION for the + global position estimate. Coordinate frame is right- + handed, Z-axis up (GPS frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) + vn : GPS velocity in cm/s in NORTH direction in earth-fixed NED frame (int16_t) + ve : GPS velocity in cm/s in EAST direction in earth-fixed NED frame (int16_t) + vd : GPS velocity in cm/s in DOWN direction in earth-fixed NED frame (int16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + + ''' + return self.send(self.hil_gps_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, vn, ve, vd, cog, satellites_visible)) + + def hil_optical_flow_encode(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return MAVLink_hil_optical_flow_message(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance) + + def hil_optical_flow_send(self, time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance): + ''' + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical + mouse sensor) + + time_usec : Timestamp (microseconds, synced to UNIX time or since system boot) (uint64_t) + sensor_id : Sensor ID (uint8_t) + integration_time_us : Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. (uint32_t) + integrated_x : Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) (float) + integrated_y : Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) (float) + integrated_xgyro : RH rotation around X axis (rad) (float) + integrated_ygyro : RH rotation around Y axis (rad) (float) + integrated_zgyro : RH rotation around Z axis (rad) (float) + temperature : Temperature * 100 in centi-degrees Celsius (int16_t) + quality : Optical flow quality / confidence. 0: no valid flow, 255: maximum quality (uint8_t) + time_delta_distance_us : Time in microseconds since the distance was sampled. (uint32_t) + distance : Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. (float) + + ''' + return self.send(self.hil_optical_flow_encode(time_usec, sensor_id, integration_time_us, integrated_x, integrated_y, integrated_xgyro, integrated_ygyro, integrated_zgyro, temperature, quality, time_delta_distance_us, distance)) + + def hil_state_quaternion_encode(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return MAVLink_hil_state_quaternion_message(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc) + + def hil_state_quaternion_send(self, time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc): + ''' + Sent from simulation to autopilot, avoids in contrast to HIL_STATE + singularities. This packet is useful for high + throughput applications such as hardware in the loop + simulations. + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + attitude_quaternion : Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) (float) + rollspeed : Body frame roll / phi angular speed (rad/s) (float) + pitchspeed : Body frame pitch / theta angular speed (rad/s) (float) + yawspeed : Body frame yaw / psi angular speed (rad/s) (float) + lat : Latitude, expressed as * 1E7 (int32_t) + lon : Longitude, expressed as * 1E7 (int32_t) + alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) + vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) + vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) + vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) + ind_airspeed : Indicated airspeed, expressed as m/s * 100 (uint16_t) + true_airspeed : True airspeed, expressed as m/s * 100 (uint16_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + + ''' + return self.send(self.hil_state_quaternion_encode(time_usec, attitude_quaternion, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, ind_airspeed, true_airspeed, xacc, yacc, zacc)) + + def scaled_imu2_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu2_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu2_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for secondary 9DOF sensor setup. This message + should contain the scaled values to the described + units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu2_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def log_request_list_encode(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return MAVLink_log_request_list_message(target_system, target_component, start, end) + + def log_request_list_send(self, target_system, target_component, start, end): + ''' + Request a list of available logs. On some systems calling this may + stop on-board logging until LOG_REQUEST_END is called. + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + start : First log id (0 for first available) (uint16_t) + end : Last log id (0xffff for last available) (uint16_t) + + ''' + return self.send(self.log_request_list_encode(target_system, target_component, start, end)) + + def log_entry_encode(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return MAVLink_log_entry_message(id, num_logs, last_log_num, time_utc, size) + + def log_entry_send(self, id, num_logs, last_log_num, time_utc, size): + ''' + Reply to LOG_REQUEST_LIST + + id : Log id (uint16_t) + num_logs : Total number of logs (uint16_t) + last_log_num : High log number (uint16_t) + time_utc : UTC timestamp of log in seconds since 1970, or 0 if not available (uint32_t) + size : Size of the log (may be approximate) in bytes (uint32_t) + + ''' + return self.send(self.log_entry_encode(id, num_logs, last_log_num, time_utc, size)) + + def log_request_data_encode(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return MAVLink_log_request_data_message(target_system, target_component, id, ofs, count) + + def log_request_data_send(self, target_system, target_component, id, ofs, count): + ''' + Request a chunk of a log + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (uint32_t) + + ''' + return self.send(self.log_request_data_encode(target_system, target_component, id, ofs, count)) + + def log_data_encode(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return MAVLink_log_data_message(id, ofs, count, data) + + def log_data_send(self, id, ofs, count, data): + ''' + Reply to LOG_REQUEST_DATA + + id : Log id (from LOG_ENTRY reply) (uint16_t) + ofs : Offset into the log (uint32_t) + count : Number of bytes (zero for end of log) (uint8_t) + data : log data (uint8_t) + + ''' + return self.send(self.log_data_encode(id, ofs, count, data)) + + def log_erase_encode(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_erase_message(target_system, target_component) + + def log_erase_send(self, target_system, target_component): + ''' + Erase all logs + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_erase_encode(target_system, target_component)) + + def log_request_end_encode(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return MAVLink_log_request_end_message(target_system, target_component) + + def log_request_end_send(self, target_system, target_component): + ''' + Stop log transfer and resume normal logging + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + + ''' + return self.send(self.log_request_end_encode(target_system, target_component)) + + def gps_inject_data_encode(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return MAVLink_gps_inject_data_message(target_system, target_component, len, data) + + def gps_inject_data_send(self, target_system, target_component, len, data): + ''' + data for injecting into the onboard GPS (used for DGPS) + + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + len : data length (uint8_t) + data : raw data (110 is enough for 12 satellites of RTCMv2) (uint8_t) + + ''' + return self.send(self.gps_inject_data_encode(target_system, target_component, len, data)) + + def gps2_raw_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return MAVLink_gps2_raw_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age) + + def gps2_raw_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age): + ''' + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS + frame). + + time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) + fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) (int32_t) + eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + epv : GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX (uint16_t) + vel : GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX (uint16_t) + cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX (uint16_t) + satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) + dgps_numch : Number of DGPS satellites (uint8_t) + dgps_age : Age of DGPS info (uint32_t) + + ''' + return self.send(self.gps2_raw_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible, dgps_numch, dgps_age)) + + def power_status_encode(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return MAVLink_power_status_message(Vcc, Vservo, flags) + + def power_status_send(self, Vcc, Vservo, flags): + ''' + Power supply status + + Vcc : 5V rail voltage in millivolts (uint16_t) + Vservo : servo rail voltage in millivolts (uint16_t) + flags : power supply status flags (see MAV_POWER_STATUS enum) (uint16_t) + + ''' + return self.send(self.power_status_encode(Vcc, Vservo, flags)) + + def serial_control_encode(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return MAVLink_serial_control_message(device, flags, timeout, baudrate, count, data) + + def serial_control_send(self, device, flags, timeout, baudrate, count, data): + ''' + Control a serial port. This can be used for raw access to an onboard + serial peripheral such as a GPS or telemetry radio. It + is designed to make it possible to update the devices + firmware via MAVLink messages or change the devices + settings. A message with zero bytes can be used to + change just the baudrate. + + device : See SERIAL_CONTROL_DEV enum (uint8_t) + flags : See SERIAL_CONTROL_FLAG enum (uint8_t) + timeout : Timeout for reply data in milliseconds (uint16_t) + baudrate : Baudrate of transfer. Zero means no change. (uint32_t) + count : how many bytes in this transfer (uint8_t) + data : serial data (uint8_t) + + ''' + return self.send(self.serial_control_encode(device, flags, timeout, baudrate, count, data)) + + def gps_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def gps2_rtk_encode(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return MAVLink_gps2_rtk_message(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses) + + def gps2_rtk_send(self, time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses): + ''' + RTK GPS data. Gives information on the relative baseline calculation + the GPS is reporting + + time_last_baseline_ms : Time since boot of last baseline message received in ms. (uint32_t) + rtk_receiver_id : Identification of connected RTK receiver. (uint8_t) + wn : GPS Week Number of last baseline (uint16_t) + tow : GPS Time of Week of last baseline (uint32_t) + rtk_health : GPS-specific health report for RTK data. (uint8_t) + rtk_rate : Rate of baseline messages being received by GPS, in HZ (uint8_t) + nsats : Current number of sats used for RTK calculation. (uint8_t) + baseline_coords_type : Coordinate system of baseline. 0 == ECEF, 1 == NED (uint8_t) + baseline_a_mm : Current baseline in ECEF x or NED north component in mm. (int32_t) + baseline_b_mm : Current baseline in ECEF y or NED east component in mm. (int32_t) + baseline_c_mm : Current baseline in ECEF z or NED down component in mm. (int32_t) + accuracy : Current estimate of baseline accuracy. (uint32_t) + iar_num_hypotheses : Current number of integer ambiguity hypotheses. (int32_t) + + ''' + return self.send(self.gps2_rtk_encode(time_last_baseline_ms, rtk_receiver_id, wn, tow, rtk_health, rtk_rate, nsats, baseline_coords_type, baseline_a_mm, baseline_b_mm, baseline_c_mm, accuracy, iar_num_hypotheses)) + + def scaled_imu3_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return MAVLink_scaled_imu3_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) + + def scaled_imu3_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): + ''' + The RAW IMU readings for 3rd 9DOF sensor setup. This message should + contain the scaled values to the described units + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + xacc : X acceleration (mg) (int16_t) + yacc : Y acceleration (mg) (int16_t) + zacc : Z acceleration (mg) (int16_t) + xgyro : Angular speed around X axis (millirad /sec) (int16_t) + ygyro : Angular speed around Y axis (millirad /sec) (int16_t) + zgyro : Angular speed around Z axis (millirad /sec) (int16_t) + xmag : X Magnetic field (milli tesla) (int16_t) + ymag : Y Magnetic field (milli tesla) (int16_t) + zmag : Z Magnetic field (milli tesla) (int16_t) + + ''' + return self.send(self.scaled_imu3_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) + + def data_transmission_handshake_encode(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return MAVLink_data_transmission_handshake_message(type, size, width, height, packets, payload, jpg_quality) + + def data_transmission_handshake_send(self, type, size, width, height, packets, payload, jpg_quality): + ''' + + + type : type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) (uint8_t) + size : total data size in bytes (set on ACK only) (uint32_t) + width : Width of a matrix or image (uint16_t) + height : Height of a matrix or image (uint16_t) + packets : number of packets beeing sent (set on ACK only) (uint16_t) + payload : payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) (uint8_t) + jpg_quality : JPEG quality out of [1,100] (uint8_t) + + ''' + return self.send(self.data_transmission_handshake_encode(type, size, width, height, packets, payload, jpg_quality)) + + def encapsulated_data_encode(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return MAVLink_encapsulated_data_message(seqnr, data) + + def encapsulated_data_send(self, seqnr, data): + ''' + + + seqnr : sequence number (starting with 0 on every transmission) (uint16_t) + data : image data bytes (uint8_t) + + ''' + return self.send(self.encapsulated_data_encode(seqnr, data)) + + def distance_sensor_encode(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return MAVLink_distance_sensor_message(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance) + + def distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance): + ''' + + + time_boot_ms : Time since system boot (uint32_t) + min_distance : Minimum distance the sensor can measure in centimeters (uint16_t) + max_distance : Maximum distance the sensor can measure in centimeters (uint16_t) + current_distance : Current distance reading (uint16_t) + type : Type from MAV_DISTANCE_SENSOR enum. (uint8_t) + id : Onboard ID of the sensor (uint8_t) + orientation : Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. (uint8_t) + covariance : Measurement covariance in centimeters, 0 for unknown / invalid readings (uint8_t) + + ''' + return self.send(self.distance_sensor_encode(time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance)) + + def terrain_request_encode(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return MAVLink_terrain_request_message(lat, lon, grid_spacing, mask) + + def terrain_request_send(self, lat, lon, grid_spacing, mask): + ''' + Request for terrain data and terrain status + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + mask : Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) (uint64_t) + + ''' + return self.send(self.terrain_request_encode(lat, lon, grid_spacing, mask)) + + def terrain_data_encode(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return MAVLink_terrain_data_message(lat, lon, grid_spacing, gridbit, data) + + def terrain_data_send(self, lat, lon, grid_spacing, gridbit, data): + ''' + Terrain data sent from GCS. The lat/lon and grid_spacing must be the + same as a lat/lon from a TERRAIN_REQUEST + + lat : Latitude of SW corner of first grid (degrees *10^7) (int32_t) + lon : Longitude of SW corner of first grid (in degrees *10^7) (int32_t) + grid_spacing : Grid spacing in meters (uint16_t) + gridbit : bit within the terrain request mask (uint8_t) + data : Terrain data in meters AMSL (int16_t) + + ''' + return self.send(self.terrain_data_encode(lat, lon, grid_spacing, gridbit, data)) + + def terrain_check_encode(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return MAVLink_terrain_check_message(lat, lon) + + def terrain_check_send(self, lat, lon): + ''' + Request that the vehicle report terrain height at the given location. + Used by GCS to check if vehicle has all terrain data + needed for a mission. + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + + ''' + return self.send(self.terrain_check_encode(lat, lon)) + + def terrain_report_encode(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return MAVLink_terrain_report_message(lat, lon, spacing, terrain_height, current_height, pending, loaded) + + def terrain_report_send(self, lat, lon, spacing, terrain_height, current_height, pending, loaded): + ''' + Response from a TERRAIN_CHECK request + + lat : Latitude (degrees *10^7) (int32_t) + lon : Longitude (degrees *10^7) (int32_t) + spacing : grid spacing (zero if terrain at this location unavailable) (uint16_t) + terrain_height : Terrain height in meters AMSL (float) + current_height : Current vehicle height above lat/lon terrain height (meters) (float) + pending : Number of 4x4 terrain blocks waiting to be received or read from disk (uint16_t) + loaded : Number of 4x4 terrain blocks in memory (uint16_t) + + ''' + return self.send(self.terrain_report_encode(lat, lon, spacing, terrain_height, current_height, pending, loaded)) + + def scaled_pressure2_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure2_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure2_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 2nd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure2_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def att_pos_mocap_encode(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return MAVLink_att_pos_mocap_message(time_usec, q, x, y, z) + + def att_pos_mocap_send(self, time_usec, q, x, y, z): + ''' + Motion capture attitude and position + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + q : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (float) + x : X position in meters (NED) (float) + y : Y position in meters (NED) (float) + z : Z position in meters (NED) (float) + + ''' + return self.send(self.att_pos_mocap_encode(time_usec, q, x, y, z)) + + def set_actuator_control_target_encode(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_set_actuator_control_target_message(time_usec, group_mlx, target_system, target_component, controls) + + def set_actuator_control_target_send(self, time_usec, group_mlx, target_system, target_component, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + target_system : System ID (uint8_t) + target_component : Component ID (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.set_actuator_control_target_encode(time_usec, group_mlx, target_system, target_component, controls)) + + def actuator_control_target_encode(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return MAVLink_actuator_control_target_message(time_usec, group_mlx, controls) + + def actuator_control_target_send(self, time_usec, group_mlx, controls): + ''' + Set the vehicle attitude and body angular rates. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + group_mlx : Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. (uint8_t) + controls : Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. (float) + + ''' + return self.send(self.actuator_control_target_encode(time_usec, group_mlx, controls)) + + def altitude_encode(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return MAVLink_altitude_message(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance) + + def altitude_send(self, time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance): + ''' + The current system altitude. + + time_usec : Timestamp (milliseconds since system boot) (uint64_t) + altitude_monotonic : This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. (float) + altitude_amsl : This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. (float) + altitude_local : This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. (float) + altitude_relative : This is the altitude above the home position. It resets on each change of the current home position. (float) + altitude_terrain : This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. (float) + bottom_clearance : This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. (float) + + ''' + return self.send(self.altitude_encode(time_usec, altitude_monotonic, altitude_amsl, altitude_local, altitude_relative, altitude_terrain, bottom_clearance)) + + def resource_request_encode(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return MAVLink_resource_request_message(request_id, uri_type, uri, transfer_type, storage) + + def resource_request_send(self, request_id, uri_type, uri, transfer_type, storage): + ''' + The autopilot is requesting a resource (file, binary, other type of + data) + + request_id : Request ID. This ID should be re-used when sending back URI contents (uint8_t) + uri_type : The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary (uint8_t) + uri : The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) (uint8_t) + transfer_type : The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. (uint8_t) + storage : The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). (uint8_t) + + ''' + return self.send(self.resource_request_encode(request_id, uri_type, uri, transfer_type, storage)) + + def scaled_pressure3_encode(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return MAVLink_scaled_pressure3_message(time_boot_ms, press_abs, press_diff, temperature) + + def scaled_pressure3_send(self, time_boot_ms, press_abs, press_diff, temperature): + ''' + Barometer readings for 3rd barometer + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + press_abs : Absolute pressure (hectopascal) (float) + press_diff : Differential pressure 1 (hectopascal) (float) + temperature : Temperature measurement (0.01 degrees celsius) (int16_t) + + ''' + return self.send(self.scaled_pressure3_encode(time_boot_ms, press_abs, press_diff, temperature)) + + def follow_target_encode(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return MAVLink_follow_target_message(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state) + + def follow_target_send(self, timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state): + ''' + current motion information from a designated system + + timestamp : Timestamp in milliseconds since system boot (uint64_t) + est_capabilities : bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) (uint8_t) + lat : Latitude (WGS84), in degrees * 1E7 (int32_t) + lon : Longitude (WGS84), in degrees * 1E7 (int32_t) + alt : AMSL, in meters (float) + vel : target velocity (0,0,0) for unknown (float) + acc : linear target acceleration (0,0,0) for unknown (float) + attitude_q : (1 0 0 0 for unknown) (float) + rates : (0 0 0 for unknown) (float) + position_cov : eph epv (float) + custom_state : button states or switches of a tracker device (uint64_t) + + ''' + return self.send(self.follow_target_encode(timestamp, est_capabilities, lat, lon, alt, vel, acc, attitude_q, rates, position_cov, custom_state)) + + def control_system_state_encode(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return MAVLink_control_system_state_message(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate) + + def control_system_state_send(self, time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate): + ''' + The smoothed, monotonic system state used to feed the control loops of + the system. + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + x_acc : X acceleration in body frame (float) + y_acc : Y acceleration in body frame (float) + z_acc : Z acceleration in body frame (float) + x_vel : X velocity in body frame (float) + y_vel : Y velocity in body frame (float) + z_vel : Z velocity in body frame (float) + x_pos : X position in local frame (float) + y_pos : Y position in local frame (float) + z_pos : Z position in local frame (float) + airspeed : Airspeed, set to -1 if unknown (float) + vel_variance : Variance of body velocity estimate (float) + pos_variance : Variance in local position (float) + q : The attitude, represented as Quaternion (float) + roll_rate : Angular rate in roll axis (float) + pitch_rate : Angular rate in pitch axis (float) + yaw_rate : Angular rate in yaw axis (float) + + ''' + return self.send(self.control_system_state_encode(time_usec, x_acc, y_acc, z_acc, x_vel, y_vel, z_vel, x_pos, y_pos, z_pos, airspeed, vel_variance, pos_variance, q, roll_rate, pitch_rate, yaw_rate)) + + def battery_status_encode(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return MAVLink_battery_status_message(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining) + + def battery_status_send(self, id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining): + ''' + Battery information + + id : Battery ID (uint8_t) + battery_function : Function of the battery (uint8_t) + type : Type (chemistry) of the battery (uint8_t) + temperature : Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. (int16_t) + voltages : Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. (uint16_t) + current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) + current_consumed : Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate (int32_t) + energy_consumed : Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate (int32_t) + battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery (int8_t) + + ''' + return self.send(self.battery_status_encode(id, battery_function, type, temperature, voltages, current_battery, current_consumed, energy_consumed, battery_remaining)) + + def autopilot_version_encode(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return MAVLink_autopilot_version_message(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid) + + def autopilot_version_send(self, capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid): + ''' + Version and capability of autopilot software + + capabilities : bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) (uint64_t) + flight_sw_version : Firmware version number (uint32_t) + middleware_sw_version : Middleware version number (uint32_t) + os_sw_version : Operating system version number (uint32_t) + board_version : HW / board version (last 8 bytes should be silicon ID, if any) (uint32_t) + flight_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + middleware_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + os_custom_version : Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. (uint8_t) + vendor_id : ID of the board vendor (uint16_t) + product_id : ID of the product (uint16_t) + uid : UID if provided by hardware (uint64_t) + + ''' + return self.send(self.autopilot_version_encode(capabilities, flight_sw_version, middleware_sw_version, os_sw_version, board_version, flight_custom_version, middleware_custom_version, os_custom_version, vendor_id, product_id, uid)) + + def landing_target_encode(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return MAVLink_landing_target_message(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y) + + def landing_target_send(self, time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y): + ''' + The location of a landing area captured from a downward facing camera + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + target_num : The ID of the target if multiple targets are present (uint8_t) + frame : MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. (uint8_t) + angle_x : X-axis angular offset (in radians) of the target from the center of the image (float) + angle_y : Y-axis angular offset (in radians) of the target from the center of the image (float) + distance : Distance to the target from the vehicle in meters (float) + size_x : Size in radians of target along x-axis (float) + size_y : Size in radians of target along y-axis (float) + + ''' + return self.send(self.landing_target_encode(time_usec, target_num, frame, angle_x, angle_y, distance, size_x, size_y)) + + def vibration_encode(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return MAVLink_vibration_message(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2) + + def vibration_send(self, time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2): + ''' + Vibration levels and accelerometer clipping + + time_usec : Timestamp (micros since boot or Unix epoch) (uint64_t) + vibration_x : Vibration levels on X-axis (float) + vibration_y : Vibration levels on Y-axis (float) + vibration_z : Vibration levels on Z-axis (float) + clipping_0 : first accelerometer clipping count (uint32_t) + clipping_1 : second accelerometer clipping count (uint32_t) + clipping_2 : third accelerometer clipping count (uint32_t) + + ''' + return self.send(self.vibration_encode(time_usec, vibration_x, vibration_y, vibration_z, clipping_0, clipping_1, clipping_2)) + + def home_position_encode(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_home_position_message(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def home_position_send(self, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION + command. The position the system will return to and + land on. The position is set automatically by the + system during the takeoff in case it was not + explicitely set by the operator before or after. The + position the system will return to and land on. The + global and local positions encode the position in the + respective coordinate frames, while the q parameter + encodes the orientation of the surface. Under normal + conditions it describes the heading and terrain slope, + which can be used by the aircraft to adjust the + approach. The approach 3D vector describes the point + to which the system should fly in normal flight mode + and then perform a landing sequence along the vector. + + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.home_position_encode(latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def set_home_position_encode(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return MAVLink_set_home_position_message(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z) + + def set_home_position_send(self, target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z): + ''' + The position the system will return to and land on. The position is + set automatically by the system during the takeoff in + case it was not explicitely set by the operator before + or after. The global and local positions encode the + position in the respective coordinate frames, while + the q parameter encodes the orientation of the + surface. Under normal conditions it describes the + heading and terrain slope, which can be used by the + aircraft to adjust the approach. The approach 3D + vector describes the point to which the system should + fly in normal flight mode and then perform a landing + sequence along the vector. + + target_system : System ID. (uint8_t) + latitude : Latitude (WGS84), in degrees * 1E7 (int32_t) + longitude : Longitude (WGS84, in degrees * 1E7 (int32_t) + altitude : Altitude (AMSL), in meters * 1000 (positive for up) (int32_t) + x : Local X position of this position in the local coordinate frame (float) + y : Local Y position of this position in the local coordinate frame (float) + z : Local Z position of this position in the local coordinate frame (float) + q : World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground (float) + approach_x : Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_y : Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + approach_z : Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. (float) + + ''' + return self.send(self.set_home_position_encode(target_system, latitude, longitude, altitude, x, y, z, q, approach_x, approach_y, approach_z)) + + def message_interval_encode(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return MAVLink_message_interval_message(message_id, interval_us) + + def message_interval_send(self, message_id, interval_us): + ''' + This interface replaces DATA_STREAM + + message_id : The ID of the requested MAVLink message. v1.0 is limited to 254 messages. (uint16_t) + interval_us : The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. (int32_t) + + ''' + return self.send(self.message_interval_encode(message_id, interval_us)) + + def extended_sys_state_encode(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return MAVLink_extended_sys_state_message(vtol_state, landed_state) + + def extended_sys_state_send(self, vtol_state, landed_state): + ''' + Provides state for additional features + + vtol_state : The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. (uint8_t) + landed_state : The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. (uint8_t) + + ''' + return self.send(self.extended_sys_state_encode(vtol_state, landed_state)) + + def adsb_vehicle_encode(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return MAVLink_adsb_vehicle_message(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk) + + def adsb_vehicle_send(self, ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk): + ''' + The location and information of an ADSB vehicle + + ICAO_address : ICAO address (uint32_t) + lat : Latitude, expressed as degrees * 1E7 (int32_t) + lon : Longitude, expressed as degrees * 1E7 (int32_t) + altitude_type : Type from ADSB_ALTITUDE_TYPE enum (uint8_t) + altitude : Altitude(ASL) in millimeters (int32_t) + heading : Course over ground in centidegrees (uint16_t) + hor_velocity : The horizontal velocity in centimeters/second (uint16_t) + ver_velocity : The vertical velocity in centimeters/second, positive is up (int16_t) + callsign : The callsign, 8+null (char) + emitter_type : Type from ADSB_EMITTER_TYPE enum (uint8_t) + tslc : Time since last communication in seconds (uint8_t) + flags : Flags to indicate various statuses including valid data fields (uint16_t) + squawk : Squawk code (uint16_t) + + ''' + return self.send(self.adsb_vehicle_encode(ICAO_address, lat, lon, altitude_type, altitude, heading, hor_velocity, ver_velocity, callsign, emitter_type, tslc, flags, squawk)) + + def v2_extension_encode(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return MAVLink_v2_extension_message(target_network, target_system, target_component, message_type, payload) + + def v2_extension_send(self, target_network, target_system, target_component, message_type, payload): + ''' + Message implementing parts of the V2 payload specs in V1 frames for + transitional support. + + target_network : Network ID (0 for broadcast) (uint8_t) + target_system : System ID (0 for broadcast) (uint8_t) + target_component : Component ID (0 for broadcast) (uint8_t) + message_type : A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. (uint16_t) + payload : Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. (uint8_t) + + ''' + return self.send(self.v2_extension_encode(target_network, target_system, target_component, message_type, payload)) + + def memory_vect_encode(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return MAVLink_memory_vect_message(address, ver, type, value) + + def memory_vect_send(self, address, ver, type, value): + ''' + Send raw controller memory. The use of this message is discouraged for + normal packets, but a quite efficient way for testing + new messages and getting experimental debug output. + + address : Starting address of the debug variables (uint16_t) + ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) + type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) + value : Memory contents at specified address (int8_t) + + ''' + return self.send(self.memory_vect_encode(address, ver, type, value)) + + def debug_vect_encode(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return MAVLink_debug_vect_message(name, time_usec, x, y, z) + + def debug_vect_send(self, name, time_usec, x, y, z): + ''' + + + name : Name (char) + time_usec : Timestamp (uint64_t) + x : x (float) + y : y (float) + z : z (float) + + ''' + return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) + + def named_value_float_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return MAVLink_named_value_float_message(time_boot_ms, name, value) + + def named_value_float_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as float. The use of this message is discouraged + for normal packets, but a quite efficient way for + testing new messages and getting experimental debug + output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Floating point value (float) + + ''' + return self.send(self.named_value_float_encode(time_boot_ms, name, value)) + + def named_value_int_encode(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return MAVLink_named_value_int_message(time_boot_ms, name, value) + + def named_value_int_send(self, time_boot_ms, name, value): + ''' + Send a key-value pair as integer. The use of this message is + discouraged for normal packets, but a quite efficient + way for testing new messages and getting experimental + debug output. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + name : Name of the debug variable (char) + value : Signed integer value (int32_t) + + ''' + return self.send(self.named_value_int_encode(time_boot_ms, name, value)) + + def statustext_encode(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return MAVLink_statustext_message(severity, text) + + def statustext_send(self, severity, text): + ''' + Status text message. These messages are printed in yellow in the COMM + console of QGroundControl. WARNING: They consume quite + some bandwidth, so use only for important status and + error messages. If implemented wisely, these messages + are buffered on the MCU and sent only at a limited + rate (e.g. 10 Hz). + + severity : Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. (uint8_t) + text : Status text message, without null termination character (char) + + ''' + return self.send(self.statustext_encode(severity, text)) + + def debug_encode(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return MAVLink_debug_message(time_boot_ms, ind, value) + + def debug_send(self, time_boot_ms, ind, value): + ''' + Send a debug value. The index is used to discriminate between values. + These values show up in the plot of QGroundControl as + DEBUG N. + + time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) + ind : index of debug variable (uint8_t) + value : DEBUG value (float) + + ''' + return self.send(self.debug_encode(time_boot_ms, ind, value)) + diff --git a/pymavlink/dialects/v10/ualberta.xml b/pymavlink/dialects/v10/ualberta.xml new file mode 100644 index 0000000..bb57e84 --- /dev/null +++ b/pymavlink/dialects/v10/ualberta.xml @@ -0,0 +1,76 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + + Raw input pulse widts sent to output + + + Inputs are normalized using calibration, the converted back to raw pulse widths for output + + + dfsdfs + + + dfsfds + + + dfsdfsdfs + + + + Navigation filter mode + + + AHRS mode + + + INS/GPS initialization mode + + + INS/GPS mode + + + + Mode currently commanded by pilot + + sdf + + + dfs + + + Rotomotion mode + + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/pymavlink/dist/pymavlink-1.1.72-py2.7-linux-x86_64.egg b/pymavlink/dist/pymavlink-1.1.72-py2.7-linux-x86_64.egg new file mode 100644 index 0000000..78f090f Binary files /dev/null and b/pymavlink/dist/pymavlink-1.1.72-py2.7-linux-x86_64.egg differ diff --git a/pymavlink/examples/__init__.py b/pymavlink/examples/__init__.py new file mode 100644 index 0000000..95eeffc --- /dev/null +++ b/pymavlink/examples/__init__.py @@ -0,0 +1 @@ +'''This folder contains various example scripts demonstrating MAVLink functionality.''' diff --git a/pymavlink/examples/apmsetrate.py b/pymavlink/examples/apmsetrate.py new file mode 100755 index 0000000..1b98b17 --- /dev/null +++ b/pymavlink/examples/apmsetrate.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python + +''' +set stream rate on an APM +''' + +import sys, struct, time, os + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) + +parser.add_argument("--baudrate", type=int, + help="master port baud rate", default=115200) +parser.add_argument("--device", required=True, help="serial device") +parser.add_argument("--rate", default=4, type=int, help="requested stream rate") +parser.add_argument("--source-system", dest='SOURCE_SYSTEM', type=int, + default=255, help='MAVLink source system for this GCS') +parser.add_argument("--showmessages", action='store_true', + help="show incoming messages", default=False) +args = parser.parse_args() + +from pymavlink import mavutil + +def wait_heartbeat(m): + '''wait for a heartbeat so we know the target system IDs''' + print("Waiting for APM heartbeat") + m.wait_heartbeat() + print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system)) + +def show_messages(m): + '''show incoming mavlink messages''' + while True: + msg = m.recv_match(blocking=True) + if not msg: + return + if msg.get_type() == "BAD_DATA": + if mavutil.all_printable(msg.data): + sys.stdout.write(msg.data) + sys.stdout.flush() + else: + print(msg) + +# create a mavlink serial instance +master = mavutil.mavlink_connection(args.device, baud=args.baudrate) + +# wait for the heartbeat msg to find the system ID +wait_heartbeat(master) + +print("Sending all stream request for rate %u" % args.rate) +for i in range(0, 3): + master.mav.request_data_stream_send(master.target_system, master.target_component, + mavutil.mavlink.MAV_DATA_STREAM_ALL, args.rate, 1) +if args.showmessages: + show_messages(master) diff --git a/pymavlink/examples/bwtest.py b/pymavlink/examples/bwtest.py new file mode 100755 index 0000000..2398ce5 --- /dev/null +++ b/pymavlink/examples/bwtest.py @@ -0,0 +1,51 @@ +#!/usr/bin/env python + +''' +check bandwidth of link +''' + +import sys, struct, time, os + +from pymavlink import mavutil + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) + +parser.add_argument("--baudrate", type=int, + help="master port baud rate", default=115200) +parser.add_argument("--device", required=True, help="serial device") +args = parser.parse_args() + +# create a mavlink serial instance +master = mavutil.mavlink_connection(args.device, baud=args.baudrate) + +t1 = time.time() + +counts = {} + +bytes_sent = 0 +bytes_recv = 0 + +while True: + master.mav.heartbeat_send(1, 2,3,4,5) + master.mav.sys_status_send(1, 2, 3, 4, 5, 6, 7) + master.mav.gps_raw_send(1, 2, 3, 4, 5, 6, 7, 8, 9) + master.mav.attitude_send(1, 2, 3, 4, 5, 6, 7) + master.mav.vfr_hud_send(1, 2, 3, 4, 5, 6) + while master.port.inWaiting() > 0: + m = master.recv_msg() + if m == None: break + if m.get_type() not in counts: + counts[m.get_type()] = 0 + counts[m.get_type()] += 1 + t2 = time.time() + if t2 - t1 > 1.0: + print("%u sent, %u received, %u errors bwin=%.1f kB/s bwout=%.1f kB/s" % ( + master.mav.total_packets_sent, + master.mav.total_packets_received, + master.mav.total_receive_errors, + 0.001*(master.mav.total_bytes_received-bytes_recv)/(t2-t1), + 0.001*(master.mav.total_bytes_sent-bytes_sent)/(t2-t1))) + bytes_sent = master.mav.total_bytes_sent + bytes_recv = master.mav.total_bytes_received + t1 = t2 diff --git a/pymavlink/examples/magtest.py b/pymavlink/examples/magtest.py new file mode 100755 index 0000000..228254b --- /dev/null +++ b/pymavlink/examples/magtest.py @@ -0,0 +1,113 @@ +#!/usr/bin/env python + +''' +rotate APMs on bench to test magnetometers + +''' + +import sys, os, time +from math import radians + +from pymavlink import mavutil + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) + +parser.add_argument("--device1", required=True, help="mavlink device1") +parser.add_argument("--device2", required=True, help="mavlink device2") +parser.add_argument("--baudrate", type=int, + help="master port baud rate", default=115200) +args = parser.parse_args() + +def set_attitude(rc3, rc4): + global mav1, mav2 + values = [ 65535 ] * 8 + values[2] = rc3 + values[3] = rc4 + mav1.mav.rc_channels_override_send(mav1.target_system, mav1.target_component, *values) + mav2.mav.rc_channels_override_send(mav2.target_system, mav2.target_component, *values) + + +# create a mavlink instance +mav1 = mavutil.mavlink_connection(args.device1, baud=args.baudrate) + +# create a mavlink instance +mav2 = mavutil.mavlink_connection(args.device2, baud=args.baudrate) + +print("Waiting for HEARTBEAT") +mav1.wait_heartbeat() +mav2.wait_heartbeat() +print("Heartbeat from APM (system %u component %u)" % (mav1.target_system, mav1.target_system)) +print("Heartbeat from APM (system %u component %u)" % (mav2.target_system, mav2.target_system)) + +print("Waiting for MANUAL mode") +mav1.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True) +mav2.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True) + +print("Setting declination") +mav1.mav.param_set_send(mav1.target_system, mav1.target_component, + 'COMPASS_DEC', radians(12.33)) +mav2.mav.param_set_send(mav2.target_system, mav2.target_component, + 'COMPASS_DEC', radians(12.33)) + + +set_attitude(1060, 1160) + +event = mavutil.periodic_event(30) +pevent = mavutil.periodic_event(0.3) +rc3_min = 1060 +rc3_max = 1850 +rc4_min = 1080 +rc4_max = 1500 +rc3 = rc3_min +rc4 = 1160 +delta3 = 2 +delta4 = 1 +use_pitch = 1 + +MAV_ACTION_CALIBRATE_GYRO = 17 +mav1.mav.action_send(mav1.target_system, mav1.target_component, MAV_ACTION_CALIBRATE_GYRO) +mav2.mav.action_send(mav2.target_system, mav2.target_component, MAV_ACTION_CALIBRATE_GYRO) + +print("Waiting for gyro calibration") +mav1.recv_match(type='ACTION_ACK') +mav2.recv_match(type='ACTION_ACK') + +print("Resetting mag offsets") +mav1.mav.set_mag_offsets_send(mav1.target_system, mav1.target_component, 0, 0, 0) +mav2.mav.set_mag_offsets_send(mav2.target_system, mav2.target_component, 0, 0, 0) + +def TrueHeading(SERVO_OUTPUT_RAW): + p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min) + return 172 + p*(326 - 172) + +while True: + mav1.recv_msg() + mav2.recv_msg() + if event.trigger(): + if not use_pitch: + rc4 = 1160 + set_attitude(rc3, rc4) + rc3 += delta3 + if rc3 > rc3_max or rc3 < rc3_min: + delta3 = -delta3 + use_pitch ^= 1 + rc4 += delta4 + if rc4 > rc4_max or rc4 < rc4_min: + delta4 = -delta4 + if pevent.trigger(): + print("hdg1: %3u hdg2: %3u ofs1: %4u, %4u, %4u ofs2: %4u, %4u, %4u" % ( + mav1.messages['VFR_HUD'].heading, + mav2.messages['VFR_HUD'].heading, + mav1.messages['SENSOR_OFFSETS'].mag_ofs_x, + mav1.messages['SENSOR_OFFSETS'].mag_ofs_y, + mav1.messages['SENSOR_OFFSETS'].mag_ofs_z, + mav2.messages['SENSOR_OFFSETS'].mag_ofs_x, + mav2.messages['SENSOR_OFFSETS'].mag_ofs_y, + mav2.messages['SENSOR_OFFSETS'].mag_ofs_z, + )) + time.sleep(0.01) + +# 314M 326G +# 160M 172G + diff --git a/pymavlink/examples/mav2pcap.py b/pymavlink/examples/mav2pcap.py new file mode 100755 index 0000000..2498db7 --- /dev/null +++ b/pymavlink/examples/mav2pcap.py @@ -0,0 +1,228 @@ +#!/usr/bin/env python + +# Copyright 2012, Holger Steinhaus +# Released under the GNU GPL version 3 or later + +# This program packetizes a binary MAVLink stream. The resulting packets are stored into a PCAP file, which is +# compatible to tools like Wireshark. + +# The program tries to synchronize to the packet structure in a robust way, using the SOF magic, the potential +# packet length information and the next SOF magic. Additionally the CRC is verified. + +# Hint: A MAVLink protocol dissector (parser) for Wireshark may be generated by mavgen.py. + +# dependency: Python construct library (python-construct on Debian/Ubuntu), "easy_install construct" elsewhere + + +import sys +import os + +from pymavlink import mavutil + +from construct import ULInt16, Struct, Byte, Bytes, Const +from construct.core import FieldError +from argparse import ArgumentParser, FileType + + +MAVLINK_MAGIC = 0xfe +write_junk = True + +# copied from ardupilotmega.h (git changeset 694536afb882068f50da1fc296944087aa207f9f, Dec 02 2012 +MAVLINK_MESSAGE_CRCS = (50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 242, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 0, 0, 0, 0, 235, 93, 124, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 234, 73, 181, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0) + + +import __builtin__ +import struct + +# Helper class for writing pcap files +class pcap: + """ + Used under the terms of GNU GPL v3. + Original author: Neale Pickett + see http://dirtbags.net/py-pcap.html + """ + _MAGIC = 0xA1B2C3D4 + def __init__(self, stream, mode='rb', snaplen=65535, linktype=1): + try: + self.stream = __builtin__.open(stream, mode) + except TypeError: + self.stream = stream + try: + # Try reading + hdr = self.stream.read(24) + except IOError: + hdr = None + + if hdr: + # We're in read mode + self._endian = pcap.None + for endian in '<>': + (self.magic,) = struct.unpack(endian + 'I', hdr[:4]) + if self.magic == pcap._MAGIC: + self._endian = endian + break + if not self._endian: + raise IOError('Not a pcap file') + (self.magic, version_major, version_minor, + self.thiszone, self.sigfigs, + self.snaplen, self.linktype) = struct.unpack(self._endian + 'IHHIIII', hdr) + if (version_major, version_minor) != (2, 4): + raise IOError('Cannot handle file version %d.%d' % (version_major, + version_minor)) + else: + # We're in write mode + self._endian = '=' + self.magic = pcap._MAGIC + version_major = 2 + version_minor = 4 + self.thiszone = 0 + self.sigfigs = 0 + self.snaplen = snaplen + self.linktype = linktype + hdr = struct.pack(self._endian + 'IHHIIII', + self.magic, version_major, version_minor, + self.thiszone, self.sigfigs, + self.snaplen, self.linktype) + self.stream.write(hdr) + self.version = (version_major, version_minor) + + def read(self): + hdr = self.stream.read(16) + if not hdr: + return + (tv_sec, tv_usec, caplen, length) = struct.unpack(self._endian + 'IIII', hdr) + datum = self.stream.read(caplen) + return ((tv_sec, tv_usec, length), datum) + + def write(self, packet): + (header, datum) = packet + (tv_sec, tv_usec, length) = header + hdr = struct.pack(self._endian + 'IIII', tv_sec, tv_usec, length, len(datum)) + self.stream.write(hdr) + self.stream.write(datum) + + def __iter__(self): + while True: + r = self.read() + if not r: + break + yield r + + +def find_next_frame(data): + """ + find a potential start of frame + """ + return data.find('\xfe') + + +def parse_header(data): + """ + split up header information (using construct) + """ + mavlink_header = Struct('header', + Const(Byte('magic'), MAVLINK_MAGIC), + Byte('plength'), + Byte('sequence'), + Byte('sysid'), + Byte('compid'), + Byte('msgid'), + ) + return mavlink_header.parse(data[0:6]) + + +def write_packet(number, data, flags, pkt_length): + pcap_header = (number, flags, pkt_length) + pcap_file.write((pcap_header, data)) + + +def convert_file(mavlink_file, pcap_file): + # the whole file is read in a bunch - room for improvement... + data = mavlink_file.read() + + i=0 + done = False + skipped_char = None + junk = '' + cnt_ok = 0 + cnt_junk = 0 + cnt_crc = 0 + + while not done: + i+=1 + # look for potential start of frame + next_sof = find_next_frame(data) + if next_sof > 0: + print("skipped " + str(next_sof) + " bytes") + if write_junk: + if skipped_char != None: + junk = skipped_char + data[:next_sof] + skipped_char = None + write_packet(i, junk, 0x03, len(junk)) + data = data[next_sof:] + data[:6] + cnt_junk += 1 + + # assume, our 0xFE was the start of a packet + header = parse_header(data) + payload_len = header['plength'] + pkt_length = 6 + payload_len + 2 + try: + pkt_crc = ULInt16('crc').parse(data[pkt_length-2:pkt_length]) + except FieldError: + # ups, no more data + done = True + continue + + # peek for the next SOF + try: + cc = mavutil.x25crc(data[1:6+payload_len]) + cc.accumulate(chr(MAVLINK_MESSAGE_CRCS[header['msgid']])) + x25_crc = cc.crc + if x25_crc != pkt_crc: + crc_flag = 0x1 + else: + crc_flag = 0 + next_magic = data[pkt_length] + if chr(MAVLINK_MAGIC) != next_magic: + # damn, retry + print("packet %d has invalid length, crc error: %d" % (i, crc_flag)) + + # skip one char to look for a new SOF next round, stow away skipped char + skipped_char = data[0] + data = data[1:] + continue + + # we can consider it a packet now + pkt = data[:pkt_length] + write_packet(i, pkt, crc_flag, len(pkt)) + print("packet %d ok, crc error: %d" % (i, crc_flag)) + data = data[pkt_length:] + + if crc_flag: + cnt_crc += 1 + else: + cnt_ok += 1 + + + except IndexError: + # ups, no more packets + done = True + print("converted %d valid packets, %d crc errors, %d junk fragments (total %f%% of junk)" % (cnt_ok, cnt_crc, cnt_junk, 100.*float(cnt_junk+cnt_crc)/(cnt_junk+cnt_ok+cnt_crc))) + +############################################################################### + +parser = ArgumentParser() +parser.add_argument("input_file", type=FileType('rb')) +parser.add_argument("output_file", type=FileType('wb')) +args = parser.parse_args() + + +mavlink_file = args.input_file +args.output_file.close() +pcap_file = pcap(args.output_file.name, args.output_file.mode, linktype=147) # special trick: linktype USER0 + +convert_file(mavlink_file, pcap_file) + +mavlink_file.close() +#pcap_file.close() diff --git a/pymavlink/examples/mav_accel.py b/pymavlink/examples/mav_accel.py new file mode 100755 index 0000000..b55ee82 --- /dev/null +++ b/pymavlink/examples/mav_accel.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python + +''' +show accel calibration for a set of logs +''' + +import sys, time, os + +from argparse import ArgumentParser +parser = ArgumentParser() +parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps") +parser.add_argument("--planner", action='store_true', help="use planner file format") +parser.add_argument("--robust", action='store_true', help="Enable robust parsing (skip over bad data)") +parser.add_argument("logs", metavar="LOG", nargs="+") + +args = parser.parse_args() + +from pymavlink import mavutil + + +def process(logfile): + '''display accel cal for a log file''' + mlog = mavutil.mavlink_connection(filename, + planner_format=args.planner, + notimestamps=args.notimestamps, + robust_parsing=args.robust) + + m = mlog.recv_match(type='SENSOR_OFFSETS') + if m is not None: + z_sensor = (m.accel_cal_z - 9.805) * (4096/9.81) + print("accel cal %5.2f %5.2f %5.2f %6u %s" % ( + m.accel_cal_x, m.accel_cal_y, m.accel_cal_z, + z_sensor, + logfile)) + + +total = 0.0 +for filename in args.logs: + process(filename) diff --git a/pymavlink/examples/mavgps.py b/pymavlink/examples/mavgps.py new file mode 100755 index 0000000..003d78b --- /dev/null +++ b/pymavlink/examples/mavgps.py @@ -0,0 +1,70 @@ +#!/usr/bin/python +""" +Allows connection of the uBlox u-Center software to +a uBlox GPS device connected to a PX4 or Pixhawk device, +using Mavlink's SERIAL_CONTROL support to route serial +traffic to/from the GPS, and exposing the data to u-Center +via a local TCP connection. + +@author: Matthew Lloyd (github@matthewlloyd.net) +""" + +from pymavlink import mavutil +from argparse import ArgumentParser +import socket + + +def main(): + parser = ArgumentParser(description=__doc__) + parser.add_argument("--mavport", required=True, + help="Mavlink port name") + parser.add_argument("--mavbaud", type=int, + help="Mavlink port baud rate", default=115200) + parser.add_argument("--devnum", default=2, type=int, + help="PX4 UART device number (defaults to GPS port)") + parser.add_argument("--devbaud", default=38400, type=int, + help="PX4 UART baud rate (defaults to u-Blox GPS baud)") + parser.add_argument("--tcpport", default=1001, type=int, + help="local TCP port (defaults to %(default)s)") + parser.add_argument("--tcpaddr", default='127.0.0.1', type=str, + help="local TCP address (defaults to %(default)s)") + parser.add_argument("--debug", default=0, type=int, + help="debug level") + parser.add_argument("--buffsize", default=128, type=int, + help="buffer size") + args = parser.parse_args() + + print("Connecting to MAVLINK...") + mav_serialport = mavutil.MavlinkSerialPort( + args.mavport, args.mavbaud, + devnum=args.devnum, devbaud=args.devbaud, debug=args.debug) + + listen_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + listen_sock.bind((args.tcpaddr, args.tcpport)) + listen_sock.listen(1) + + print("Waiting for a TCP connection.") + print("Use tcp://%s:%d in u-Center." % (args.tcpaddr, args.tcpport)) + conn_sock, addr = listen_sock.accept() + conn_sock.setblocking(0) # non-blocking mode + print("TCP connection accepted. Use Ctrl+C to exit.") + + while True: + try: + data = conn_sock.recv(args.buffsize) + if data: + if args.debug >= 1: + print '>', len(data) + mav_serialport.write(data) + except socket.error: + pass + + data = mav_serialport.read(args.buffsize) + if data: + if args.debug >= 1: + print '<', len(data) + conn_sock.send(data) + + +if __name__ == '__main__': + main() diff --git a/pymavlink/examples/mavtcpsniff.py b/pymavlink/examples/mavtcpsniff.py new file mode 100755 index 0000000..778efed --- /dev/null +++ b/pymavlink/examples/mavtcpsniff.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python + +''' +connect as a client to two tcpip ports on localhost with mavlink packets. pass them both directions, and show packets in human-readable format on-screen. + +this is useful if +* you have two SITL instances you want to connect to each other and see the comms. +* you have any tcpip based mavlink happening, and want something better than tcpdump + +hint: +* you can use netcat/nc to do interesting redorection things with each end if you want to. + +Copyright Sept 2012 David "Buzz" Bussenschutt +Released under GNU GPL version 3 or later +''' + +import sys, time, os, struct + +from pymavlink import mavutil +#from pymavlink import mavlinkv10 as mavlink + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) +parser.add_argument("srcport", type=int) +parser.add_argument("dstport", type=int) + +args = parser.parse_args() + +msrc = mavutil.mavlink_connection('tcp:localhost:{}'.format(args.srcport), planner_format=False, + notimestamps=True, + robust_parsing=True) + +mdst = mavutil.mavlink_connection('tcp:localhost:{}'.format(args.dstport), planner_format=False, + notimestamps=True, + robust_parsing=True) + + +# simple basic byte pass through, no logging or viewing of packets, or analysis etc +#while True: +# # L -> R +# m = msrc.recv(); +# mdst.write(m); +# # R -> L +# m2 = mdst.recv(); +# msrc.write(m2); + + +# similar to the above, but with human-readable display of packets on stdout. +# in this use case we abuse the self.logfile_raw() function to allow +# us to use the recv_match function ( whch is then calling recv_msg ) , to still get the raw data stream +# which we pass off to the other mavlink connection without any interference. +# because internally it will call logfile_raw.write() for us. + +# here we hook raw output of one to the raw input of the other, and vice versa: +msrc.logfile_raw = mdst +mdst.logfile_raw = msrc + +while True: + # L -> R + l = msrc.recv_match(); + if l is not None: + l_last_timestamp = 0 + if l.get_type() != 'BAD_DATA': + l_timestamp = getattr(l, '_timestamp', None) + if not l_timestamp: + l_timestamp = l_last_timestamp + l_last_timestamp = l_timestamp + + print("--> %s.%02u: %s\n" % ( + time.strftime("%Y-%m-%d %H:%M:%S", + time.localtime(l._timestamp)), + int(l._timestamp*100.0)%100, l)) + + # R -> L + r = mdst.recv_match(); + if r is not None: + r_last_timestamp = 0 + if r.get_type() != 'BAD_DATA': + r_timestamp = getattr(r, '_timestamp', None) + if not r_timestamp: + r_timestamp = r_last_timestamp + r_last_timestamp = r_timestamp + + print("<-- %s.%02u: %s\n" % ( + time.strftime("%Y-%m-%d %H:%M:%S", + time.localtime(r._timestamp)), + int(r._timestamp*100.0)%100, r)) + + + diff --git a/pymavlink/examples/mavtest.py b/pymavlink/examples/mavtest.py new file mode 100755 index 0000000..f409024 --- /dev/null +++ b/pymavlink/examples/mavtest.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python + +import sys, os + +from pymavlink import mavlinkv10 as mavlink + +class fifo(object): + def __init__(self): + self.buf = [] + def write(self, data): + self.buf += data + return len(data) + def read(self): + return self.buf.pop(0) + +# we will use a fifo as an encode/decode buffer +f = fifo() + +# create a mavlink instance, which will do IO on file object 'f' +mav = mavlink.MAVLink(f) + +# set the WP_RADIUS parameter on the MAV at the end of the link +mav.param_set_send(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32) + +# alternatively, produce a MAVLink_param_set object +# this can be sent via your own transport if you like +m = mav.param_set_encode(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32) + +# get the encoded message as a buffer +b = m.get_msgbuf() + +# decode an incoming message +m2 = mav.decode(b) + +# show what fields it has +print("Got a message with id %u and fields %s" % (m2.get_msgId(), m2.get_fieldnames())) + +# print out the fields +print(m2) diff --git a/pymavlink/examples/mavtester.py b/pymavlink/examples/mavtester.py new file mode 100755 index 0000000..5e090f8 --- /dev/null +++ b/pymavlink/examples/mavtester.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python + +''' +test mavlink messages +''' + +import sys, struct, time, os +from curses import ascii + +from pymavlink import mavutil + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) + +parser.add_argument("--baudrate", type=int, + help="master port baud rate", default=115200) +parser.add_argument("--device", required=True, help="serial device") +parser.add_argument("--source-system", dest='SOURCE_SYSTEM', type=int, + default=255, help='MAVLink source system for this GCS') +args = parser.parse_args() + +def wait_heartbeat(m): + '''wait for a heartbeat so we know the target system IDs''' + print("Waiting for APM heartbeat") + msg = m.recv_match(type='SATBALL_SENS', blocking=True) + print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system)) + +# create a mavlink serial instance +master = mavutil.mavlink_connection(args.device, baud=args.baudrate, source_system=args.SOURCE_SYSTEM) + +# wait for the heartbeat msg to find the system ID +wait_heartbeat(master) + +print("Sending all message types") diff --git a/pymavlink/examples/testcon.py b/pymavlink/examples/testcon.py new file mode 100755 index 0000000..2398ce5 --- /dev/null +++ b/pymavlink/examples/testcon.py @@ -0,0 +1,51 @@ +#!/usr/bin/env python + +''' +check bandwidth of link +''' + +import sys, struct, time, os + +from pymavlink import mavutil + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) + +parser.add_argument("--baudrate", type=int, + help="master port baud rate", default=115200) +parser.add_argument("--device", required=True, help="serial device") +args = parser.parse_args() + +# create a mavlink serial instance +master = mavutil.mavlink_connection(args.device, baud=args.baudrate) + +t1 = time.time() + +counts = {} + +bytes_sent = 0 +bytes_recv = 0 + +while True: + master.mav.heartbeat_send(1, 2,3,4,5) + master.mav.sys_status_send(1, 2, 3, 4, 5, 6, 7) + master.mav.gps_raw_send(1, 2, 3, 4, 5, 6, 7, 8, 9) + master.mav.attitude_send(1, 2, 3, 4, 5, 6, 7) + master.mav.vfr_hud_send(1, 2, 3, 4, 5, 6) + while master.port.inWaiting() > 0: + m = master.recv_msg() + if m == None: break + if m.get_type() not in counts: + counts[m.get_type()] = 0 + counts[m.get_type()] += 1 + t2 = time.time() + if t2 - t1 > 1.0: + print("%u sent, %u received, %u errors bwin=%.1f kB/s bwout=%.1f kB/s" % ( + master.mav.total_packets_sent, + master.mav.total_packets_received, + master.mav.total_receive_errors, + 0.001*(master.mav.total_bytes_received-bytes_recv)/(t2-t1), + 0.001*(master.mav.total_bytes_sent-bytes_sent)/(t2-t1))) + bytes_sent = master.mav.total_bytes_sent + bytes_recv = master.mav.total_bytes_received + t1 = t2 diff --git a/pymavlink/examples/wptogpx.py b/pymavlink/examples/wptogpx.py new file mode 100755 index 0000000..e31ef5e --- /dev/null +++ b/pymavlink/examples/wptogpx.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python + +''' +example program to extract GPS data from a waypoint file, and create a GPX +file, for loading into google earth +''' + +import sys, struct, time, os + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) +parser.add_argument("wpfiles", metavar="WP_FILE", nargs="+") +args = parser.parse_args() + +from pymavlink import mavutil, mavwp + + +def wp_to_gpx(infilename, outfilename): + '''convert a wp file to a GPX file''' + + wp = mavwp.MAVWPLoader() + wp.load(infilename) + outf = open(outfilename, mode='w') + + def process_wp(w, i): + t = time.localtime(i) + outf.write(''' + %s + WP %u + +''' % (w.x, w.y, w.z, i)) + + def add_header(): + outf.write(''' + +''') + + def add_footer(): + outf.write(''' + +''') + + add_header() + + count = 0 + for i in range(wp.count()): + w = wp.wp(i) + if w.frame == 3: + w.z += wp.wp(0).z + if w.command == 16: + process_wp(w, i) + count += 1 + add_footer() + print("Created %s with %u points" % (outfilename, count)) + + +for infilename in args.wpfiles: + outfilename = infilename + '.gpx' + wp_to_gpx(infilename, outfilename) diff --git a/pymavlink/fgFDM.py b/pymavlink/fgFDM.py new file mode 100644 index 0000000..d381afa --- /dev/null +++ b/pymavlink/fgFDM.py @@ -0,0 +1,212 @@ +#!/usr/bin/env python +# parse and construct FlightGear NET FDM packets +# Andrew Tridgell, November 2011 +# released under GNU GPL version 2 or later + +import struct, math + +class fgFDMError(Exception): + '''fgFDM error class''' + def __init__(self, msg): + Exception.__init__(self, msg) + self.message = 'fgFDMError: ' + msg + +class fgFDMVariable(object): + '''represent a single fgFDM variable''' + def __init__(self, index, arraylength, units): + self.index = index + self.arraylength = arraylength + self.units = units + +class fgFDMVariableList(object): + '''represent a list of fgFDM variable''' + def __init__(self): + self.vars = {} + self._nextidx = 0 + + def add(self, varname, arraylength=1, units=None): + self.vars[varname] = fgFDMVariable(self._nextidx, arraylength, units=units) + self._nextidx += arraylength + +class fgFDM(object): + '''a flightgear native FDM parser/generator''' + def __init__(self): + '''init a fgFDM object''' + self.FG_NET_FDM_VERSION = 24 + self.pack_string = '>I 4x 3d 6f 11f 3f 2f I 4I 4f 4f 4f 4f 4f 4f 4f 4f 4f I 4f I 3I 3f 3f 3f I i f 10f' + self.values = [0]*98 + + self.FG_MAX_ENGINES = 4 + self.FG_MAX_WHEELS = 3 + self.FG_MAX_TANKS = 4 + + # supported unit mappings + self.unitmap = { + ('radians', 'degrees') : math.degrees(1), + ('rps', 'dps') : math.degrees(1), + ('feet', 'meters') : 0.3048, + ('fps', 'mps') : 0.3048, + ('knots', 'mps') : 0.514444444, + ('knots', 'fps') : 0.514444444/0.3048, + ('fpss', 'mpss') : 0.3048, + ('seconds', 'minutes') : 60, + ('seconds', 'hours') : 3600, + } + + # build a mapping between variable name and index in the values array + # note that the order of this initialisation is critical - it must + # match the wire structure + self.mapping = fgFDMVariableList() + self.mapping.add('version') + + # position + self.mapping.add('longitude', units='radians') # geodetic (radians) + self.mapping.add('latitude', units='radians') # geodetic (radians) + self.mapping.add('altitude', units='meters') # above sea level (meters) + self.mapping.add('agl', units='meters') # above ground level (meters) + + # attitude + self.mapping.add('phi', units='radians') # roll (radians) + self.mapping.add('theta', units='radians') # pitch (radians) + self.mapping.add('psi', units='radians') # yaw or true heading (radians) + self.mapping.add('alpha', units='radians') # angle of attack (radians) + self.mapping.add('beta', units='radians') # side slip angle (radians) + + # Velocities + self.mapping.add('phidot', units='rps') # roll rate (radians/sec) + self.mapping.add('thetadot', units='rps') # pitch rate (radians/sec) + self.mapping.add('psidot', units='rps') # yaw rate (radians/sec) + self.mapping.add('vcas', units='fps') # calibrated airspeed + self.mapping.add('climb_rate', units='fps') # feet per second + self.mapping.add('v_north', units='fps') # north velocity in local/body frame, fps + self.mapping.add('v_east', units='fps') # east velocity in local/body frame, fps + self.mapping.add('v_down', units='fps') # down/vertical velocity in local/body frame, fps + self.mapping.add('v_wind_body_north', units='fps') # north velocity in local/body frame + self.mapping.add('v_wind_body_east', units='fps') # east velocity in local/body frame + self.mapping.add('v_wind_body_down', units='fps') # down/vertical velocity in local/body + + # Accelerations + self.mapping.add('A_X_pilot', units='fpss') # X accel in body frame ft/sec^2 + self.mapping.add('A_Y_pilot', units='fpss') # Y accel in body frame ft/sec^2 + self.mapping.add('A_Z_pilot', units='fpss') # Z accel in body frame ft/sec^2 + + # Stall + self.mapping.add('stall_warning') # 0.0 - 1.0 indicating the amount of stall + self.mapping.add('slip_deg', units='degrees') # slip ball deflection + + # Engine status + self.mapping.add('num_engines') # Number of valid engines + self.mapping.add('eng_state', self.FG_MAX_ENGINES) # Engine state (off, cranking, running) + self.mapping.add('rpm', self.FG_MAX_ENGINES) # Engine RPM rev/min + self.mapping.add('fuel_flow', self.FG_MAX_ENGINES) # Fuel flow gallons/hr + self.mapping.add('fuel_px', self.FG_MAX_ENGINES) # Fuel pressure psi + self.mapping.add('egt', self.FG_MAX_ENGINES) # Exhuast gas temp deg F + self.mapping.add('cht', self.FG_MAX_ENGINES) # Cylinder head temp deg F + self.mapping.add('mp_osi', self.FG_MAX_ENGINES) # Manifold pressure + self.mapping.add('tit', self.FG_MAX_ENGINES) # Turbine Inlet Temperature + self.mapping.add('oil_temp', self.FG_MAX_ENGINES) # Oil temp deg F + self.mapping.add('oil_px', self.FG_MAX_ENGINES) # Oil pressure psi + + # Consumables + self.mapping.add('num_tanks') # Max number of fuel tanks + self.mapping.add('fuel_quantity', self.FG_MAX_TANKS) + + # Gear status + self.mapping.add('num_wheels') + self.mapping.add('wow', self.FG_MAX_WHEELS) + self.mapping.add('gear_pos', self.FG_MAX_WHEELS) + self.mapping.add('gear_steer', self.FG_MAX_WHEELS) + self.mapping.add('gear_compression', self.FG_MAX_WHEELS) + + # Environment + self.mapping.add('cur_time', units='seconds') # current unix time + self.mapping.add('warp', units='seconds') # offset in seconds to unix time + self.mapping.add('visibility', units='meters') # visibility in meters (for env. effects) + + # Control surface positions (normalized values) + self.mapping.add('elevator') + self.mapping.add('elevator_trim_tab') + self.mapping.add('left_flap') + self.mapping.add('right_flap') + self.mapping.add('left_aileron') + self.mapping.add('right_aileron') + self.mapping.add('rudder') + self.mapping.add('nose_wheel') + self.mapping.add('speedbrake') + self.mapping.add('spoilers') + + self._packet_size = struct.calcsize(self.pack_string) + + self.set('version', self.FG_NET_FDM_VERSION) + + if len(self.values) != self.mapping._nextidx: + raise fgFDMError('Invalid variable list in initialisation') + + def packet_size(self): + '''return expected size of FG FDM packets''' + return self._packet_size + + def convert(self, value, fromunits, tounits): + '''convert a value from one set of units to another''' + if fromunits == tounits: + return value + if (fromunits,tounits) in self.unitmap: + return value * self.unitmap[(fromunits,tounits)] + if (tounits,fromunits) in self.unitmap: + return value / self.unitmap[(tounits,fromunits)] + raise fgFDMError("unknown unit mapping (%s,%s)" % (fromunits, tounits)) + + + def units(self, varname): + '''return the default units of a variable''' + if not varname in self.mapping.vars: + raise fgFDMError('Unknown variable %s' % varname) + return self.mapping.vars[varname].units + + + def variables(self): + '''return a list of available variables''' + return sorted(list(self.mapping.vars.keys()), + key = lambda v : self.mapping.vars[v].index) + + + def get(self, varname, idx=0, units=None): + '''get a variable value''' + if not varname in self.mapping.vars: + raise fgFDMError('Unknown variable %s' % varname) + if idx >= self.mapping.vars[varname].arraylength: + raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % ( + varname, idx, self.mapping.vars[varname].arraylength)) + value = self.values[self.mapping.vars[varname].index + idx] + if units: + value = self.convert(value, self.mapping.vars[varname].units, units) + return value + + def set(self, varname, value, idx=0, units=None): + '''set a variable value''' + if not varname in self.mapping.vars: + raise fgFDMError('Unknown variable %s' % varname) + if idx >= self.mapping.vars[varname].arraylength: + raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % ( + varname, idx, self.mapping.vars[varname].arraylength)) + if units: + value = self.convert(value, units, self.mapping.vars[varname].units) + # avoid range errors when packing into 4 byte floats + if math.isinf(value) or math.isnan(value) or math.fabs(value) > 3.4e38: + value = 0 + self.values[self.mapping.vars[varname].index + idx] = value + + def parse(self, buf): + '''parse a FD FDM buffer''' + try: + t = struct.unpack(self.pack_string, buf) + except struct.error as msg: + raise fgFDMError('unable to parse - %s' % msg) + self.values = list(t) + + def pack(self): + '''pack a FD FDM buffer from current values''' + for i in range(len(self.values)): + if math.isnan(self.values[i]): + self.values[i] = 0 + return struct.pack(self.pack_string, *self.values) diff --git a/pymavlink/files/archlinux/PKGBUILD b/pymavlink/files/archlinux/PKGBUILD new file mode 100644 index 0000000..ef38225 --- /dev/null +++ b/pymavlink/files/archlinux/PKGBUILD @@ -0,0 +1,52 @@ +# Maintainer: Thomas Gubler +pkgname=python2-mavlink-git +pkgver=20140119 +pkgrel=1 +pkgdesc="Python implementation of the MAVLink protocol" +arch=(any) +url="http://qgroundcontrol.org/mavlink/pymavlink" +license=('LGPL3') +depends=('python2') +makedepends=('git' 'python2' 'python2-setuptools') +optdepends=() +provides=('python2-mavlink-git') +conflicts=() +options=(!emptydirs) + +_gitroot="https://github.com/mavlink/mavlink/" +_gitname="mavlink" +_subfoldername="pymavlink" + +build() { + cd "$srcdir" + msg "Connecting to GIT server..." + + if [ -d $_gitname ] ; then + cd $_gitname && git pull origin + msg "The local files are updated." + else + git clone $_gitroot $_gitname + fi + + msg "GIT checkout done or server timeout" + + cd "$srcdir/$_gitname/$_subfoldername" + git clean -fdx + + msg "Starting make..." + python2 setup.py build +} + +package() { + cd "$srcdir/$_gitname/$_subfoldername" + python2 setup.py install --prefix=/usr --root=$pkgdir/ --optimize=1 + + install -Dm644 "$srcdir/$_gitname/$_subfoldername/README.txt" "$pkgdir/usr/share/licenses/$pkgname/README.txt" +} + +pkgver() { + cd "$pkgname" + printf "r%s.%s" "$(git rev-list --count HEAD)" "$(git rev-parse --short HEAD)" +} + +# vim:set ts=2 sw=2 et: diff --git a/pymavlink/generator/C/include_v0.9/checksum.h b/pymavlink/generator/C/include_v0.9/checksum.h new file mode 100644 index 0000000..32bf6e4 --- /dev/null +++ b/pymavlink/generator/C/include_v0.9/checksum.h @@ -0,0 +1,95 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _CHECKSUM_H_ +#define _CHECKSUM_H_ + +// Visual Studio versions before 2010 don't have stdint.h, so we just error out. +#if (defined _MSC_VER) && (_MSC_VER < 1600) +#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" +#endif + +#include + +/** + * + * CALCULATE THE CHECKSUM + * + */ + +#define X25_INIT_CRC 0xffff +#define X25_VALIDATE_CRC 0xf0b8 + +/** + * @brief Accumulate the X.25 CRC by adding one char at a time. + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new char to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) +{ + /*Accumulate one byte of data into the CRC*/ + uint8_t tmp; + + tmp = data ^ (uint8_t)(*crcAccum &0xff); + tmp ^= (tmp<<4); + *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); +} + +/** + * @brief Initiliaze the buffer for the X.25 CRC + * + * @param crcAccum the 16 bit X.25 CRC + */ +static inline void crc_init(uint16_t* crcAccum) +{ + *crcAccum = X25_INIT_CRC; +} + + +/** + * @brief Calculates the X.25 checksum on a byte buffer + * + * @param pBuffer buffer containing the byte array to hash + * @param length length of the byte array + * @return the checksum over the buffer bytes + **/ +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) +{ + uint16_t crcTmp; + crc_init(&crcTmp); + while (length--) { + crc_accumulate(*pBuffer++, &crcTmp); + } + return crcTmp; +} + +/** + * @brief Accumulate the X.25 CRC by adding an array of bytes + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new bytes to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) +{ + const uint8_t *p = (const uint8_t *)pBuffer; + while (length--) { + crc_accumulate(*p++, crcAccum); + } +} + + + + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/pymavlink/generator/C/include_v0.9/mavlink_helpers.h b/pymavlink/generator/C/include_v0.9/mavlink_helpers.h new file mode 100644 index 0000000..f3eac41 --- /dev/null +++ b/pymavlink/generator/C/include_v0.9/mavlink_helpers.h @@ -0,0 +1,550 @@ +#ifndef _MAVLINK_HELPERS_H_ +#define _MAVLINK_HELPERS_H_ + +#include "string.h" +#include "checksum.h" +#include "mavlink_types.h" + +#ifndef MAVLINK_HELPER +#define MAVLINK_HELPER +#endif + +/* + internal function to give access to the channel status for each channel + */ +MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) +{ + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; + return &m_mavlink_status[chan]; +} + +/* + internal function to give access to the channel buffer for each channel + */ +MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) +{ + +#if MAVLINK_EXTERNAL_RX_BUFFER + // No m_mavlink_message array defined in function, + // has to be defined externally +#ifndef m_mavlink_message +#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];) +#endif +#else + static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_buffer[chan]; +} + +/** + * @brief Finalize a MAVLink message with channel assignment + * + * This function calculates the checksum and sets length and aircraft id correctly. + * It assumes that the message id and the payload are already correctly set. This function + * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack + * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. + * + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length) +#endif +{ + // This code part is the same for all messages; + uint16_t checksum; + msg->magic = MAVLINK_STX; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per channel + msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; + mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; + checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); + mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); + + return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + + +/** + * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); +} +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); +} +#endif + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + +/** + * @brief Finalize a MAVLink message with channel assignment and send + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) +#endif +{ + uint16_t checksum; + uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; + uint8_t ck[2]; + mavlink_status_t *status = mavlink_get_channel_status(chan); + buf[0] = MAVLINK_STX; + buf[1] = length; + buf[2] = status->current_tx_seq; + buf[3] = mavlink_system.sysid; + buf[4] = mavlink_system.compid; + buf[5] = msgid; + status->current_tx_seq++; + checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&checksum, packet, length); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + ck[0] = (uint8_t)(checksum & 0xFF); + ck[1] = (uint8_t)(checksum >> 8); + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); + _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, packet, length); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); +} + +/** + * @brief re-send a message over a uart channel + * this is more stack efficient than re-marshalling the message + */ +MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) +{ + uint8_t ck[2]; + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); + _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +/** + * @brief Pack a message to send it over a serial byte stream + */ +MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) +{ + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); + return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; +} + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) +{ + crc_init(&msg->checksum); +} + +MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + crc_accumulate(c, &msg->checksum); +} + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. Checksum and other failures will be silently + * ignored. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to barse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @return 0 if no message could be decoded, 1 else + * + * A typical use scenario of this function call is: + * + * @code + * #include // For fixed-width uint8_t type + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + /* + default message crc function. You can override this per-system to + put this data in a different memory segment + */ +#if MAVLINK_CRC_EXTRA +#ifndef MAVLINK_MESSAGE_CRC + static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; +#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] +#endif +#endif + + +/* Enable this option to check the length of each message. +This allows invalid messages to be caught much sooner. Use if the transmission +medium is prone to missing (or extra) characters (e.g. a radio that fades in +and out). Only use if the channel will only contain messages types listed in +the headers. +*/ +#if MAVLINK_CHECK_MESSAGE_LENGTH +#ifndef MAVLINK_MESSAGE_LENGTH + static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] +#endif +#endif + + mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message + mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status + int bufferIndex = 0; + + status->msg_received = 0; + + switch (status->parse_state) + { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + rxmsg->magic = c; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received +/* Support shorter buffers than the + default maximum packet size */ +#if (MAVLINK_MAX_PAYLOAD_LEN < 255) + || c > MAVLINK_MAX_PAYLOAD_LEN +#endif + ) + { + status->buffer_overrun++; + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + } + else + { + // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 + rxmsg->len = c; + status->packet_idx = 0; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + rxmsg->seq = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + rxmsg->sysid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + rxmsg->compid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: +#if MAVLINK_CHECK_MESSAGE_LENGTH + if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) + { + status->parse_error++; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + break; + } +#endif + rxmsg->msgid = c; + mavlink_update_checksum(rxmsg, c); + if (rxmsg->len == 0) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; + mavlink_update_checksum(rxmsg, c); + if (status->packet_idx == rxmsg->len) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: +#if MAVLINK_CRC_EXTRA + mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); +#endif + if (c != (rxmsg->checksum & 0xFF)) { + // Check first checksum byte + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; + } + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + if (c != (rxmsg->checksum >> 8)) { + // Check second checksum byte + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + } + else + { + // Successfully got message + status->msg_received = 1; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; + memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); + } + break; + } + + bufferIndex++; + // If a message has been sucessfully decoded, check index + if (status->msg_received == 1) + { + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_rx_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; + } + + r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg + r_mavlink_status->parse_state = status->parse_state; + r_mavlink_status->packet_idx = status->packet_idx; + r_mavlink_status->current_rx_seq = status->current_rx_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + status->parse_error = 0; + return status->msg_received; +} + +/** + * @brief Put a bitfield of length 1-32 bit into the buffer + * + * @param b the value to add, will be encoded in the bitfield + * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. + * @param packet_index the position in the packet (the index of the first byte to use) + * @param bit_index the position in the byte (the index of the first bit to use) + * @param buffer packet buffer to write into + * @return new position of the last used byte in the buffer + */ +MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) +{ + uint16_t bits_remain = bits; + // Transform number into network order + int32_t v; + uint8_t i_bit_index, i_byte_index, curr_bits_n; +#if MAVLINK_NEED_BYTE_SWAP + union { + int32_t i; + uint8_t b[4]; + } bin, bout; + bin.i = b; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + v = bout.i; +#else + v = b; +#endif + + // buffer in + // 01100000 01000000 00000000 11110001 + // buffer out + // 11110001 00000000 01000000 01100000 + + // Existing partly filled byte (four free slots) + // 0111xxxx + + // Mask n free bits + // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 + // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 + + // Shift n bits into the right position + // out = in >> n; + + // Mask and shift bytes + i_bit_index = bit_index; + i_byte_index = packet_index; + if (bit_index > 0) + { + // If bits were available at start, they were available + // in the byte before the current index + i_byte_index--; + } + + // While bits have not been packed yet + while (bits_remain > 0) + { + // Bits still have to be packed + // there can be more than 8 bits, so + // we might have to pack them into more than one byte + + // First pack everything we can into the current 'open' byte + //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 + //FIXME + if (bits_remain <= (uint8_t)(8 - i_bit_index)) + { + // Enough space + curr_bits_n = (uint8_t)bits_remain; + } + else + { + curr_bits_n = (8 - i_bit_index); + } + + // Pack these n bits into the current byte + // Mask out whatever was at that position with ones (xxx11111) + buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); + // Put content to this position, by masking out the non-used part + buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); + + // Increment the bit index + i_bit_index += curr_bits_n; + + // Now proceed to the next byte, if necessary + bits_remain -= curr_bits_n; + if (bits_remain > 0) + { + // Offer another 8 bits / one byte + i_byte_index++; + i_bit_index = 0; + } + } + + *r_bit_index = i_bit_index; + // If a partly filled byte is present, mark this as consumed + if (i_bit_index != 7) i_byte_index++; + return i_byte_index - packet_index; +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +// To make MAVLink work on your MCU, define comm_send_ch() if you wish +// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a +// whole packet at a time + +/* + +#include "mavlink_types.h" + +void comm_send_ch(mavlink_channel_t chan, uint8_t ch) +{ + if (chan == MAVLINK_COMM_0) + { + uart0_transmit(ch); + } + if (chan == MAVLINK_COMM_1) + { + uart1_transmit(ch); + } +} + */ + +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) +{ +#ifdef MAVLINK_SEND_UART_BYTES + /* this is the more efficient approach, if the platform + defines it */ + MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); +#else + /* fallback to one byte at a time */ + uint16_t i; + for (i = 0; i < len; i++) { + comm_send_ch(chan, (uint8_t)buf[i]); + } +#endif +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/pymavlink/generator/C/include_v0.9/mavlink_types.h b/pymavlink/generator/C/include_v0.9/mavlink_types.h new file mode 100644 index 0000000..9d04155 --- /dev/null +++ b/pymavlink/generator/C/include_v0.9/mavlink_types.h @@ -0,0 +1,323 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +#include "inttypes.h" + +enum MAV_CLASS +{ + MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything + MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch + MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu + MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com + MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org + MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints + MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands + MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set + MAV_CLASS_NONE = 8, ///< No valid autopilot + MAV_CLASS_NB ///< Number of autopilot classes +}; + +enum MAV_ACTION +{ + MAV_ACTION_HOLD = 0, + MAV_ACTION_MOTORS_START = 1, + MAV_ACTION_LAUNCH = 2, + MAV_ACTION_RETURN = 3, + MAV_ACTION_EMCY_LAND = 4, + MAV_ACTION_EMCY_KILL = 5, + MAV_ACTION_CONFIRM_KILL = 6, + MAV_ACTION_CONTINUE = 7, + MAV_ACTION_MOTORS_STOP = 8, + MAV_ACTION_HALT = 9, + MAV_ACTION_SHUTDOWN = 10, + MAV_ACTION_REBOOT = 11, + MAV_ACTION_SET_MANUAL = 12, + MAV_ACTION_SET_AUTO = 13, + MAV_ACTION_STORAGE_READ = 14, + MAV_ACTION_STORAGE_WRITE = 15, + MAV_ACTION_CALIBRATE_RC = 16, + MAV_ACTION_CALIBRATE_GYRO = 17, + MAV_ACTION_CALIBRATE_MAG = 18, + MAV_ACTION_CALIBRATE_ACC = 19, + MAV_ACTION_CALIBRATE_PRESSURE = 20, + MAV_ACTION_REC_START = 21, + MAV_ACTION_REC_PAUSE = 22, + MAV_ACTION_REC_STOP = 23, + MAV_ACTION_TAKEOFF = 24, + MAV_ACTION_NAVIGATE = 25, + MAV_ACTION_LAND = 26, + MAV_ACTION_LOITER = 27, + MAV_ACTION_SET_ORIGIN = 28, + MAV_ACTION_RELAY_ON = 29, + MAV_ACTION_RELAY_OFF = 30, + MAV_ACTION_GET_IMAGE = 31, + MAV_ACTION_VIDEO_START = 32, + MAV_ACTION_VIDEO_STOP = 33, + MAV_ACTION_RESET_MAP = 34, + MAV_ACTION_RESET_PLAN = 35, + MAV_ACTION_DELAY_BEFORE_COMMAND = 36, + MAV_ACTION_ASCEND_AT_RATE = 37, + MAV_ACTION_CHANGE_MODE = 38, + MAV_ACTION_LOITER_MAX_TURNS = 39, + MAV_ACTION_LOITER_MAX_TIME = 40, + MAV_ACTION_START_HILSIM = 41, + MAV_ACTION_STOP_HILSIM = 42, + MAV_ACTION_NB ///< Number of MAV actions +}; + +enum MAV_MODE +{ + MAV_MODE_UNINIT = 0, ///< System is in undefined state + MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe + MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control + MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint + MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation + MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use + MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use + MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use + MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive + MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back +}; + +enum MAV_STATE +{ + MAV_STATE_UNINIT = 0, + MAV_STATE_BOOT, + MAV_STATE_CALIBRATING, + MAV_STATE_STANDBY, + MAV_STATE_ACTIVE, + MAV_STATE_CRITICAL, + MAV_STATE_EMERGENCY, + MAV_STATE_HILSIM, + MAV_STATE_POWEROFF +}; + +enum MAV_NAV +{ + MAV_NAV_GROUNDED = 0, + MAV_NAV_LIFTOFF, + MAV_NAV_HOLD, + MAV_NAV_WAYPOINT, + MAV_NAV_VECTOR, + MAV_NAV_RETURNING, + MAV_NAV_LANDING, + MAV_NAV_LOST, + MAV_NAV_LOITER, + MAV_NAV_FREE_DRIFT +}; + +enum MAV_TYPE +{ + MAV_GENERIC = 0, + MAV_FIXED_WING = 1, + MAV_QUADROTOR = 2, + MAV_COAXIAL = 3, + MAV_HELICOPTER = 4, + MAV_GROUND = 5, + OCU = 6, + MAV_AIRSHIP = 7, + MAV_FREE_BALLOON = 8, + MAV_ROCKET = 9, + UGV_GROUND_ROVER = 10, + UGV_SURFACE_SHIP = 11 +}; + +enum MAV_AUTOPILOT_TYPE +{ + MAV_AUTOPILOT_GENERIC = 0, + MAV_AUTOPILOT_PIXHAWK = 1, + MAV_AUTOPILOT_SLUGS = 2, + MAV_AUTOPILOT_ARDUPILOTMEGA = 3, + MAV_AUTOPILOT_NONE = 4 +}; + +enum MAV_COMPONENT +{ + MAV_COMP_ID_GPS, + MAV_COMP_ID_WAYPOINTPLANNER, + MAV_COMP_ID_BLOBTRACKER, + MAV_COMP_ID_PATHPLANNER, + MAV_COMP_ID_AIRSLAM, + MAV_COMP_ID_MAPPER, + MAV_COMP_ID_CAMERA, + MAV_COMP_ID_RADIO = 68, + MAV_COMP_ID_IMU = 200, + MAV_COMP_ID_IMU_2 = 201, + MAV_COMP_ID_IMU_3 = 202, + MAV_COMP_ID_UDP_BRIDGE = 240, + MAV_COMP_ID_UART_BRIDGE = 241, + MAV_COMP_ID_SYSTEM_CONTROL = 250 +}; + +enum MAV_FRAME +{ + MAV_FRAME_GLOBAL = 0, + MAV_FRAME_LOCAL = 1, + MAV_FRAME_MISSION = 2, + MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, + MAV_FRAME_LOCAL_ENU = 4 +}; + +enum MAVLINK_DATA_STREAM_TYPE +{ + MAVLINK_DATA_STREAM_IMG_JPEG, + MAVLINK_DATA_STREAM_IMG_BMP, + MAVLINK_DATA_STREAM_IMG_RAW8U, + MAVLINK_DATA_STREAM_IMG_RAW32U, + MAVLINK_DATA_STREAM_IMG_PGM, + MAVLINK_DATA_STREAM_IMG_PNG +}; + +#ifndef MAVLINK_MAX_PAYLOAD_LEN +// it is possible to override this, but be careful! +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length +#endif + +#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) +#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum +#define MAVLINK_NUM_CHECKSUM_BYTES 2 +#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length + +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 +#define MAVLINK_EXTENDED_HEADER_LEN 14 + +#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) + /* full fledged 32bit++ OS */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 +#else + /* small microcontrollers */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 +#endif + +#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) + +typedef struct param_union { + union { + float param_float; + int32_t param_int32; + uint32_t param_uint32; + uint8_t param_uint8; + uint8_t bytes[4]; + }; + uint8_t type; +} mavlink_param_union_t; + +typedef struct __mavlink_system { + uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t type; ///< Unused, can be used by user to store the system's type + uint8_t state; ///< Unused, can be used by user to store the system's state + uint8_t mode; ///< Unused, can be used by user to store the system's mode + uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode +} mavlink_system_t; + +typedef struct __mavlink_message { + uint16_t checksum; /// sent at end of packet + uint8_t magic; ///< protocol magic marker + uint8_t len; ///< Length of payload + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint8_t msgid; ///< ID of message in payload + uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; +} mavlink_message_t; + + +typedef struct __mavlink_extended_message { + mavlink_message_t base_msg; + int32_t extended_payload_len; ///< Length of extended payload if any + uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; +} mavlink_extended_message_t; + + +typedef enum { + MAVLINK_TYPE_CHAR = 0, + MAVLINK_TYPE_UINT8_T = 1, + MAVLINK_TYPE_INT8_T = 2, + MAVLINK_TYPE_UINT16_T = 3, + MAVLINK_TYPE_INT16_T = 4, + MAVLINK_TYPE_UINT32_T = 5, + MAVLINK_TYPE_INT32_T = 6, + MAVLINK_TYPE_UINT64_T = 7, + MAVLINK_TYPE_INT64_T = 8, + MAVLINK_TYPE_FLOAT = 9, + MAVLINK_TYPE_DOUBLE = 10 +} mavlink_message_type_t; + +#define MAVLINK_MAX_FIELDS 64 + +typedef struct __mavlink_field_info { + const char *name; // name of this field + const char *print_format; // printing format hint, or NULL + mavlink_message_type_t type; // type of this field + unsigned int array_length; // if non-zero, field is an array + unsigned int wire_offset; // offset of each field in the payload + unsigned int structure_offset; // offset in a C structure +} mavlink_field_info_t; + +// note that in this structure the order of fields is the order +// in the XML file, not necessary the wire order +typedef struct __mavlink_message_info { + const char *name; // name of the message + unsigned num_fields; // how many fields in this message + mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information +} mavlink_message_info_t; + +#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) +#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) + +// checksum is immediately after the payload bytes +#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) +#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_2, + MAVLINK_COMM_3 +} mavlink_channel_t; + +/* + * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number + * of buffers they will use. If more are used, then the result will be + * a stack overrun + */ +#ifndef MAVLINK_COMM_NUM_BUFFERS +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +# define MAVLINK_COMM_NUM_BUFFERS 16 +#else +# define MAVLINK_COMM_NUM_BUFFERS 4 +#endif +#endif + +typedef enum { + MAVLINK_PARSE_STATE_UNINIT=0, + MAVLINK_PARSE_STATE_IDLE, + MAVLINK_PARSE_STATE_GOT_STX, + MAVLINK_PARSE_STATE_GOT_SEQ, + MAVLINK_PARSE_STATE_GOT_LENGTH, + MAVLINK_PARSE_STATE_GOT_SYSID, + MAVLINK_PARSE_STATE_GOT_COMPID, + MAVLINK_PARSE_STATE_GOT_MSGID, + MAVLINK_PARSE_STATE_GOT_PAYLOAD, + MAVLINK_PARSE_STATE_GOT_CRC1 +} mavlink_parse_state_t; ///< The state machine for the comm parser + +typedef struct __mavlink_status { + uint8_t msg_received; ///< Number of received messages + uint8_t buffer_overrun; ///< Number of buffer overruns + uint8_t parse_error; ///< Number of parse errors + mavlink_parse_state_t parse_state; ///< Parsing state machine + uint8_t packet_idx; ///< Index in current packet + uint8_t current_rx_seq; ///< Sequence number of last packet received + uint8_t current_tx_seq; ///< Sequence number of last packet sent + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#define MAVLINK_BIG_ENDIAN 0 +#define MAVLINK_LITTLE_ENDIAN 1 + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/pymavlink/generator/C/include_v0.9/protocol.h b/pymavlink/generator/C/include_v0.9/protocol.h new file mode 100644 index 0000000..5283779 --- /dev/null +++ b/pymavlink/generator/C/include_v0.9/protocol.h @@ -0,0 +1,323 @@ +#ifndef _MAVLINK_PROTOCOL_H_ +#define _MAVLINK_PROTOCOL_H_ + +#include "string.h" +#include "mavlink_types.h" + +/* + If you want MAVLink on a system that is native big-endian, + you need to define NATIVE_BIG_ENDIAN +*/ +#ifdef NATIVE_BIG_ENDIAN +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) +#else +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) +#endif + +#ifndef MAVLINK_STACK_BUFFER +#define MAVLINK_STACK_BUFFER 0 +#endif + +#ifndef MAVLINK_AVOID_GCC_STACK_BUG +# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) +#endif + +#ifndef MAVLINK_ASSERT +#define MAVLINK_ASSERT(x) +#endif + +#ifndef MAVLINK_START_UART_SEND +#define MAVLINK_START_UART_SEND(chan, length) +#endif + +#ifndef MAVLINK_END_UART_SEND +#define MAVLINK_END_UART_SEND(chan, length) +#endif + +#ifdef MAVLINK_SEPARATE_HELPERS +#define MAVLINK_HELPER +#else +#define MAVLINK_HELPER static inline +#include "mavlink_helpers.h" +#endif // MAVLINK_SEPARATE_HELPERS + +/* always include the prototypes to ensure we don't get out of sync */ +MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra); +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra); +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra); +#endif +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length); +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length); +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); +#endif // MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); +MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); +MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); +MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); +MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, + uint8_t* r_bit_index, uint8_t* buffer); +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); +MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg); +#endif + +/** + * @brief Get the required buffer size for this message + */ +static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) +{ + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + +#if MAVLINK_NEED_BYTE_SWAP +static inline void byte_swap_2(char *dst, const char *src) +{ + dst[0] = src[1]; + dst[1] = src[0]; +} +static inline void byte_swap_4(char *dst, const char *src) +{ + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; +} +static inline void byte_swap_8(char *dst, const char *src) +{ + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; +} +#elif !MAVLINK_ALIGNED_FIELDS +static inline void byte_copy_2(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; +} +static inline void byte_copy_4(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + dst[3] = src[3]; +} +static inline void byte_copy_8(char *dst, const char *src) +{ + memcpy(dst, src, 8); +} +#endif + +#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b +#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b +#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b + +#if MAVLINK_NEED_BYTE_SWAP +#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#elif !MAVLINK_ALIGNED_FIELDS +#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#else +#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b +#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b +#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b +#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b +#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b +#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b +#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b +#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b +#endif + +/* + like memcpy(), but if src is NULL, do a memset to zero +*/ +static void mav_array_memcpy(void *dest, const void *src, size_t n) +{ + if (src == NULL) { + memset(dest, 0, n); + } else { + memcpy(dest, src, n); + } +} + +/* + * Place a char array into a buffer + */ +static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a uint8_t array into a buffer + */ +static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a int8_t array into a buffer + */ +static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +#if MAVLINK_NEED_BYTE_SWAP +#define _MAV_PUT_ARRAY(TYPE, V) \ +static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ +{ \ + if (b == NULL) { \ + memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ + } else { \ + uint16_t i; \ + for (i=0; imsgid = MAVLINK_MSG_ID_TEST_TYPES; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +} + +/** + * @brief Pack a test_types message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TEST_TYPES_LEN]; + _mav_put_char(buf, 0, c); + _mav_put_uint8_t(buf, 11, u8); + _mav_put_uint16_t(buf, 12, u16); + _mav_put_uint32_t(buf, 14, u32); + _mav_put_uint64_t(buf, 18, u64); + _mav_put_int8_t(buf, 26, s8); + _mav_put_int16_t(buf, 27, s16); + _mav_put_int32_t(buf, 29, s32); + _mav_put_int64_t(buf, 33, s64); + _mav_put_float(buf, 41, f); + _mav_put_double(buf, 45, d); + _mav_put_char_array(buf, 1, s, 10); + _mav_put_uint8_t_array(buf, 53, u8_array, 3); + _mav_put_uint16_t_array(buf, 56, u16_array, 3); + _mav_put_uint32_t_array(buf, 62, u32_array, 3); + _mav_put_uint64_t_array(buf, 74, u64_array, 3); + _mav_put_int8_t_array(buf, 98, s8_array, 3); + _mav_put_int16_t_array(buf, 101, s16_array, 3); + _mav_put_int32_t_array(buf, 107, s32_array, 3); + _mav_put_int64_t_array(buf, 119, s64_array, 3); + _mav_put_float_array(buf, 143, f_array, 3); + _mav_put_double_array(buf, 155, d_array, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#else + mavlink_test_types_t packet; + packet.c = c; + packet.u8 = u8; + packet.u16 = u16; + packet.u32 = u32; + packet.u64 = u64; + packet.s8 = s8; + packet.s16 = s16; + packet.s32 = s32; + packet.s64 = s64; + packet.f = f; + packet.d = d; + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +} + +/** + * @brief Encode a test_types struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param test_types C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) +{ + return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); +} + +/** + * @brief Send a test_types message + * @param chan MAVLink channel to send the message + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TEST_TYPES_LEN]; + _mav_put_char(buf, 0, c); + _mav_put_uint8_t(buf, 11, u8); + _mav_put_uint16_t(buf, 12, u16); + _mav_put_uint32_t(buf, 14, u32); + _mav_put_uint64_t(buf, 18, u64); + _mav_put_int8_t(buf, 26, s8); + _mav_put_int16_t(buf, 27, s16); + _mav_put_int32_t(buf, 29, s32); + _mav_put_int64_t(buf, 33, s64); + _mav_put_float(buf, 41, f); + _mav_put_double(buf, 45, d); + _mav_put_char_array(buf, 1, s, 10); + _mav_put_uint8_t_array(buf, 53, u8_array, 3); + _mav_put_uint16_t_array(buf, 56, u16_array, 3); + _mav_put_uint32_t_array(buf, 62, u32_array, 3); + _mav_put_uint64_t_array(buf, 74, u64_array, 3); + _mav_put_int8_t_array(buf, 98, s8_array, 3); + _mav_put_int16_t_array(buf, 101, s16_array, 3); + _mav_put_int32_t_array(buf, 107, s32_array, 3); + _mav_put_int64_t_array(buf, 119, s64_array, 3); + _mav_put_float_array(buf, 143, f_array, 3); + _mav_put_double_array(buf, 155, d_array, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +#else + mavlink_test_types_t packet; + packet.c = c; + packet.u8 = u8; + packet.u16 = u16; + packet.u32 = u32; + packet.u64 = u64; + packet.s8 = s8; + packet.s16 = s16; + packet.s32 = s32; + packet.s64 = s64; + packet.f = f; + packet.d = d; + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +#endif +} + +#endif + +// MESSAGE TEST_TYPES UNPACKING + + +/** + * @brief Get field c from test_types message + * + * @return char + */ +static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_char(msg, 0); +} + +/** + * @brief Get field s from test_types message + * + * @return string + */ +static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) +{ + return _MAV_RETURN_char_array(msg, s, 10, 1); +} + +/** + * @brief Get field u8 from test_types message + * + * @return uint8_t + */ +static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field u16 from test_types message + * + * @return uint16_t + */ +static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field u32 from test_types message + * + * @return uint32_t + */ +static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 14); +} + +/** + * @brief Get field u64 from test_types message + * + * @return uint64_t + */ +static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 18); +} + +/** + * @brief Get field s8 from test_types message + * + * @return int8_t + */ +static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 26); +} + +/** + * @brief Get field s16 from test_types message + * + * @return int16_t + */ +static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 27); +} + +/** + * @brief Get field s32 from test_types message + * + * @return int32_t + */ +static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 29); +} + +/** + * @brief Get field s64 from test_types message + * + * @return int64_t + */ +static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 33); +} + +/** + * @brief Get field f from test_types message + * + * @return float + */ +static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 41); +} + +/** + * @brief Get field d from test_types message + * + * @return double + */ +static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) +{ + return _MAV_RETURN_double(msg, 45); +} + +/** + * @brief Get field u8_array from test_types message + * + * @return uint8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) +{ + return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 53); +} + +/** + * @brief Get field u16_array from test_types message + * + * @return uint16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) +{ + return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 56); +} + +/** + * @brief Get field u32_array from test_types message + * + * @return uint32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) +{ + return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 62); +} + +/** + * @brief Get field u64_array from test_types message + * + * @return uint64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) +{ + return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 74); +} + +/** + * @brief Get field s8_array from test_types message + * + * @return int8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) +{ + return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 98); +} + +/** + * @brief Get field s16_array from test_types message + * + * @return int16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) +{ + return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 101); +} + +/** + * @brief Get field s32_array from test_types message + * + * @return int32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) +{ + return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 107); +} + +/** + * @brief Get field s64_array from test_types message + * + * @return int64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) +{ + return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 119); +} + +/** + * @brief Get field f_array from test_types message + * + * @return float_array + */ +static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) +{ + return _MAV_RETURN_float_array(msg, f_array, 3, 143); +} + +/** + * @brief Get field d_array from test_types message + * + * @return double_array + */ +static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) +{ + return _MAV_RETURN_double_array(msg, d_array, 3, 155); +} + +/** + * @brief Decode a test_types message into a struct + * + * @param msg The message to decode + * @param test_types C-struct to decode the message contents into + */ +static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) +{ +#if MAVLINK_NEED_BYTE_SWAP + test_types->c = mavlink_msg_test_types_get_c(msg); + mavlink_msg_test_types_get_s(msg, test_types->s); + test_types->u8 = mavlink_msg_test_types_get_u8(msg); + test_types->u16 = mavlink_msg_test_types_get_u16(msg); + test_types->u32 = mavlink_msg_test_types_get_u32(msg); + test_types->u64 = mavlink_msg_test_types_get_u64(msg); + test_types->s8 = mavlink_msg_test_types_get_s8(msg); + test_types->s16 = mavlink_msg_test_types_get_s16(msg); + test_types->s32 = mavlink_msg_test_types_get_s32(msg); + test_types->s64 = mavlink_msg_test_types_get_s64(msg); + test_types->f = mavlink_msg_test_types_get_f(msg); + test_types->d = mavlink_msg_test_types_get_d(msg); + mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); + mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); + mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); + mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); + mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); + mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); + mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); + mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); + mavlink_msg_test_types_get_f_array(msg, test_types->f_array); + mavlink_msg_test_types_get_d_array(msg, test_types->d_array); +#else + memcpy(test_types, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +} diff --git a/pymavlink/generator/C/include_v0.9/test/test.h b/pymavlink/generator/C/include_v0.9/test/test.h new file mode 100644 index 0000000..46b47be --- /dev/null +++ b/pymavlink/generator/C/include_v0.9/test/test.h @@ -0,0 +1,53 @@ +/** @file + * @brief MAVLink comm protocol generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_H +#define TEST_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {91, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_TEST + +// ENUM DEFINITIONS + + + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_test_types.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // TEST_H diff --git a/pymavlink/generator/C/include_v0.9/test/testsuite.h b/pymavlink/generator/C/include_v0.9/test/testsuite.h new file mode 100644 index 0000000..9b0fc04 --- /dev/null +++ b/pymavlink/generator/C/include_v0.9/test/testsuite.h @@ -0,0 +1,120 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_TESTSUITE_H +#define TEST_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_test(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_test_types_t packet_in = { + 'A', + "BCDEFGHIJ", + 230, + 17859, + 963498192, + 93372036854776941ULL, + 211, + 18639, + 963498972, + 93372036854777886LL, + 304.0, + 438.0, + { 228, 229, 230 }, + { 20147, 20148, 20149 }, + { 963500688, 963500689, 963500690 }, + { 93372036854780469, 93372036854780470, 93372036854780471 }, + { 171, 172, 173 }, + { 22487, 22488, 22489 }, + { 963503028, 963503029, 963503030 }, + { 93372036854783304, 93372036854783305, 93372036854783306 }, + { 1018.0, 1019.0, 1020.0 }, + { 1208.0, 1209.0, 1210.0 }, + }; + mavlink_test_types_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.c = packet_in.c; + packet1.u8 = packet_in.u8; + packet1.u16 = packet_in.u16; + packet1.u32 = packet_in.u32; + packet1.u64 = packet_in.u64; + packet1.s8 = packet_in.s8; + packet1.s16 = packet_in.s16; + packet1.s32 = packet_in.s32; + packet1.s64 = packet_in.s64; + packet1.f = packet_in.f; + packet1.d = packet_in.d; + + mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10); + mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); + mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); + mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i + +/** + * + * CALCULATE THE CHECKSUM + * + */ + +#define X25_INIT_CRC 0xffff +#define X25_VALIDATE_CRC 0xf0b8 + +#ifndef HAVE_CRC_ACCUMULATE +/** + * @brief Accumulate the X.25 CRC by adding one char at a time. + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new char to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) +{ + /*Accumulate one byte of data into the CRC*/ + uint8_t tmp; + + tmp = data ^ (uint8_t)(*crcAccum &0xff); + tmp ^= (tmp<<4); + *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); +} +#endif + + +/** + * @brief Initiliaze the buffer for the X.25 CRC + * + * @param crcAccum the 16 bit X.25 CRC + */ +static inline void crc_init(uint16_t* crcAccum) +{ + *crcAccum = X25_INIT_CRC; +} + + +/** + * @brief Calculates the X.25 checksum on a byte buffer + * + * @param pBuffer buffer containing the byte array to hash + * @param length length of the byte array + * @return the checksum over the buffer bytes + **/ +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) +{ + uint16_t crcTmp; + crc_init(&crcTmp); + while (length--) { + crc_accumulate(*pBuffer++, &crcTmp); + } + return crcTmp; +} + + +/** + * @brief Accumulate the X.25 CRC by adding an array of bytes + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new bytes to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) +{ + const uint8_t *p = (const uint8_t *)pBuffer; + while (length--) { + crc_accumulate(*p++, crcAccum); + } +} + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/pymavlink/generator/C/include_v1.0/mavlink_conversions.h b/pymavlink/generator/C/include_v1.0/mavlink_conversions.h new file mode 100644 index 0000000..63bcfa3 --- /dev/null +++ b/pymavlink/generator/C/include_v1.0/mavlink_conversions.h @@ -0,0 +1,211 @@ +#ifndef _MAVLINK_CONVERSIONS_H_ +#define _MAVLINK_CONVERSIONS_H_ + +/* enable math defines on Windows */ +#ifdef _MSC_VER +#ifndef _USE_MATH_DEFINES +#define _USE_MATH_DEFINES +#endif +#endif +#include + +#ifndef M_PI_2 + #define M_PI_2 ((float)asin(1)) +#endif + +/** + * @file mavlink_conversions.h + * + * These conversion functions follow the NASA rotation standards definition file + * available online. + * + * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free + * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) + * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the + * protocol as widely as possible. + * + * @author James Goppert + * @author Thomas Gubler + */ + + +/** + * Converts a quaternion to a rotation matrix + * + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + * @param dcm a 3x3 rotation matrix + */ +MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) +{ + double a = quaternion[0]; + double b = quaternion[1]; + double c = quaternion[2]; + double d = quaternion[3]; + double aSq = a * a; + double bSq = b * b; + double cSq = c * c; + double dSq = d * d; + dcm[0][0] = aSq + bSq - cSq - dSq; + dcm[0][1] = 2 * (b * c - a * d); + dcm[0][2] = 2 * (a * c + b * d); + dcm[1][0] = 2 * (b * c + a * d); + dcm[1][1] = aSq - bSq + cSq - dSq; + dcm[1][2] = 2 * (c * d - a * b); + dcm[2][0] = 2 * (b * d - a * c); + dcm[2][1] = 2 * (a * b + c * d); + dcm[2][2] = aSq - bSq - cSq + dSq; +} + + +/** + * Converts a rotation matrix to euler angles + * + * @param dcm a 3x3 rotation matrix + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + */ +MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) +{ + float phi, theta, psi; + theta = asin(-dcm[2][0]); + + if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { + phi = 0.0f; + psi = (atan2f(dcm[1][2] - dcm[0][1], + dcm[0][2] + dcm[1][1]) + phi); + + } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { + phi = 0.0f; + psi = atan2f(dcm[1][2] - dcm[0][1], + dcm[0][2] + dcm[1][1] - phi); + + } else { + phi = atan2f(dcm[2][1], dcm[2][2]); + psi = atan2f(dcm[1][0], dcm[0][0]); + } + + *roll = phi; + *pitch = theta; + *yaw = psi; +} + + +/** + * Converts a quaternion to euler angles + * + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + */ +MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) +{ + float dcm[3][3]; + mavlink_quaternion_to_dcm(quaternion, dcm); + mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); +} + + +/** + * Converts euler angles to a quaternion + * + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + */ +MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) +{ + float cosPhi_2 = cosf(roll / 2); + float sinPhi_2 = sinf(roll / 2); + float cosTheta_2 = cosf(pitch / 2); + float sinTheta_2 = sinf(pitch / 2); + float cosPsi_2 = cosf(yaw / 2); + float sinPsi_2 = sinf(yaw / 2); + quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + + sinPhi_2 * sinTheta_2 * sinPsi_2); + quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - + cosPhi_2 * sinTheta_2 * sinPsi_2); + quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + + sinPhi_2 * cosTheta_2 * sinPsi_2); + quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - + sinPhi_2 * sinTheta_2 * cosPsi_2); +} + + +/** + * Converts a rotation matrix to a quaternion + * Reference: + * - Shoemake, Quaternions, + * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf + * + * @param dcm a 3x3 rotation matrix + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + */ +MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) +{ + float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; + if (tr > 0.0f) { + float s = sqrtf(tr + 1.0f); + quaternion[0] = s * 0.5f; + s = 0.5f / s; + quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; + quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; + quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; + } else { + /* Find maximum diagonal element in dcm + * store index in dcm_i */ + int dcm_i = 0; + int i; + for (i = 1; i < 3; i++) { + if (dcm[i][i] > dcm[dcm_i][dcm_i]) { + dcm_i = i; + } + } + + int dcm_j = (dcm_i + 1) % 3; + int dcm_k = (dcm_i + 2) % 3; + + float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - + dcm[dcm_k][dcm_k]) + 1.0f); + quaternion[dcm_i + 1] = s * 0.5f; + s = 0.5f / s; + quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; + quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; + quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; + } +} + + +/** + * Converts euler angles to a rotation matrix + * + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + * @param dcm a 3x3 rotation matrix + */ +MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) +{ + float cosPhi = cosf(roll); + float sinPhi = sinf(roll); + float cosThe = cosf(pitch); + float sinThe = sinf(pitch); + float cosPsi = cosf(yaw); + float sinPsi = sinf(yaw); + + dcm[0][0] = cosThe * cosPsi; + dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; + dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; + + dcm[1][0] = cosThe * sinPsi; + dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; + dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; + + dcm[2][0] = -sinThe; + dcm[2][1] = sinPhi * cosThe; + dcm[2][2] = cosPhi * cosThe; +} + +#endif diff --git a/pymavlink/generator/C/include_v1.0/mavlink_helpers.h b/pymavlink/generator/C/include_v1.0/mavlink_helpers.h new file mode 100644 index 0000000..0fa87fc --- /dev/null +++ b/pymavlink/generator/C/include_v1.0/mavlink_helpers.h @@ -0,0 +1,676 @@ +#ifndef _MAVLINK_HELPERS_H_ +#define _MAVLINK_HELPERS_H_ + +#include "string.h" +#include "checksum.h" +#include "mavlink_types.h" +#include "mavlink_conversions.h" + +#ifndef MAVLINK_HELPER +#define MAVLINK_HELPER +#endif + +/* + * Internal function to give access to the channel status for each channel + */ +#ifndef MAVLINK_GET_CHANNEL_STATUS +MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) +{ +#ifdef MAVLINK_EXTERNAL_RX_STATUS + // No m_mavlink_status array defined in function, + // has to be defined externally +#else + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_status[chan]; +} +#endif + +/* + * Internal function to give access to the channel buffer for each channel + */ +#ifndef MAVLINK_GET_CHANNEL_BUFFER +MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) +{ + +#ifdef MAVLINK_EXTERNAL_RX_BUFFER + // No m_mavlink_buffer array defined in function, + // has to be defined externally +#else + static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_buffer[chan]; +} +#endif + +/** + * @brief Reset the status of a channel. + */ +MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) +{ + mavlink_status_t *status = mavlink_get_channel_status(chan); + status->parse_state = MAVLINK_PARSE_STATE_IDLE; +} + +/** + * @brief Finalize a MAVLink message with channel assignment + * + * This function calculates the checksum and sets length and aircraft id correctly. + * It assumes that the message id and the payload are already correctly set. This function + * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack + * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. + * + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length) +#endif +{ + // This code part is the same for all messages; + msg->magic = MAVLINK_STX; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per channel + msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; + mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; + msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &msg->checksum); +#endif + mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); + mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); + + return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + + +/** + * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); +} +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); +} +#endif + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + +/** + * @brief Finalize a MAVLink message with channel assignment and send + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) +#endif +{ + uint16_t checksum; + uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; + uint8_t ck[2]; + mavlink_status_t *status = mavlink_get_channel_status(chan); + buf[0] = MAVLINK_STX; + buf[1] = length; + buf[2] = status->current_tx_seq; + buf[3] = mavlink_system.sysid; + buf[4] = mavlink_system.compid; + buf[5] = msgid; + status->current_tx_seq++; + checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&checksum, packet, length); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + ck[0] = (uint8_t)(checksum & 0xFF); + ck[1] = (uint8_t)(checksum >> 8); + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); + _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, packet, length); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); +} + +/** + * @brief re-send a message over a uart channel + * this is more stack efficient than re-marshalling the message + */ +MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) +{ + uint8_t ck[2]; + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + // XXX use the right sequence here + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); + _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +/** + * @brief Pack a message to send it over a serial byte stream + */ +MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) +{ + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + + return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; +} + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) +{ + crc_init(&msg->checksum); +} + +MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + crc_accumulate(c, &msg->checksum); +} + +/** + * This is a varient of mavlink_frame_char() but with caller supplied + * parsing buffers. It is useful when you want to create a MAVLink + * parser in a library that doesn't use any global variables + * + * @param rxmsg parsing message buffer + * @param status parsing starus buffer + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, + mavlink_status_t* status, + uint8_t c, + mavlink_message_t* r_message, + mavlink_status_t* r_mavlink_status) +{ + /* + default message crc function. You can override this per-system to + put this data in a different memory segment + */ +#if MAVLINK_CRC_EXTRA +#ifndef MAVLINK_MESSAGE_CRC + static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; +#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] +#endif +#endif + + /* Enable this option to check the length of each message. + This allows invalid messages to be caught much sooner. Use if the transmission + medium is prone to missing (or extra) characters (e.g. a radio that fades in + and out). Only use if the channel will only contain messages types listed in + the headers. + */ +#ifdef MAVLINK_CHECK_MESSAGE_LENGTH +#ifndef MAVLINK_MESSAGE_LENGTH + static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] +#endif +#endif + + int bufferIndex = 0; + + status->msg_received = MAVLINK_FRAMING_INCOMPLETE; + + switch (status->parse_state) + { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + rxmsg->magic = c; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received +/* Support shorter buffers than the + default maximum packet size */ +#if (MAVLINK_MAX_PAYLOAD_LEN < 255) + || c > MAVLINK_MAX_PAYLOAD_LEN +#endif + ) + { + status->buffer_overrun++; + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + } + else + { + // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 + rxmsg->len = c; + status->packet_idx = 0; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + rxmsg->seq = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + rxmsg->sysid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + rxmsg->compid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: +#ifdef MAVLINK_CHECK_MESSAGE_LENGTH + if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) + { + status->parse_error++; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + break; + } +#endif + rxmsg->msgid = c; + mavlink_update_checksum(rxmsg, c); + if (rxmsg->len == 0) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; + mavlink_update_checksum(rxmsg, c); + if (status->packet_idx == rxmsg->len) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: +#if MAVLINK_CRC_EXTRA + mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); +#endif + if (c != (rxmsg->checksum & 0xFF)) { + status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1; + } else { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + } + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: + if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) { + // got a bad CRC message + status->msg_received = MAVLINK_FRAMING_BAD_CRC; + } else { + // Successfully got message + status->msg_received = MAVLINK_FRAMING_OK; + } + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; + memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); + break; + } + + bufferIndex++; + // If a message has been sucessfully decoded, check index + if (status->msg_received == MAVLINK_FRAMING_OK) + { + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_rx_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; + } + + r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg + r_mavlink_status->parse_state = status->parse_state; + r_mavlink_status->packet_idx = status->packet_idx; + r_mavlink_status->current_rx_seq = status->current_rx_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + status->parse_error = 0; + + if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) { + /* + the CRC came out wrong. We now need to overwrite the + msg CRC with the one on the wire so that if the + caller decides to forward the message anyway that + mavlink_msg_to_send_buffer() won't overwrite the + checksum + */ + r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8); + } + + return status->msg_received; +} + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. This function will return 0, 1 or + * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) + * + * Messages are parsed into an internal buffer (one for each channel). When a complete + * message is received it is copies into *returnMsg and the channel's status is + * copied into *returnStats. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan), + mavlink_get_channel_status(chan), + c, + r_message, + r_mavlink_status); +} + + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. This function will return 0 or 1. + * + * Messages are parsed into an internal buffer (one for each channel). When a complete + * message is received it is copies into *returnMsg and the channel's status is + * copied into *returnStats. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status); + if (msg_received == MAVLINK_FRAMING_BAD_CRC) { + // we got a bad CRC. Treat as a parse failure + mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); + mavlink_status_t* status = mavlink_get_channel_status(chan); + status->parse_error++; + status->msg_received = MAVLINK_FRAMING_INCOMPLETE; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + return 0; + } + return msg_received; +} + +/** + * @brief Put a bitfield of length 1-32 bit into the buffer + * + * @param b the value to add, will be encoded in the bitfield + * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. + * @param packet_index the position in the packet (the index of the first byte to use) + * @param bit_index the position in the byte (the index of the first bit to use) + * @param buffer packet buffer to write into + * @return new position of the last used byte in the buffer + */ +MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) +{ + uint16_t bits_remain = bits; + // Transform number into network order + int32_t v; + uint8_t i_bit_index, i_byte_index, curr_bits_n; +#if MAVLINK_NEED_BYTE_SWAP + union { + int32_t i; + uint8_t b[4]; + } bin, bout; + bin.i = b; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + v = bout.i; +#else + v = b; +#endif + + // buffer in + // 01100000 01000000 00000000 11110001 + // buffer out + // 11110001 00000000 01000000 01100000 + + // Existing partly filled byte (four free slots) + // 0111xxxx + + // Mask n free bits + // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 + // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 + + // Shift n bits into the right position + // out = in >> n; + + // Mask and shift bytes + i_bit_index = bit_index; + i_byte_index = packet_index; + if (bit_index > 0) + { + // If bits were available at start, they were available + // in the byte before the current index + i_byte_index--; + } + + // While bits have not been packed yet + while (bits_remain > 0) + { + // Bits still have to be packed + // there can be more than 8 bits, so + // we might have to pack them into more than one byte + + // First pack everything we can into the current 'open' byte + //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 + //FIXME + if (bits_remain <= (uint8_t)(8 - i_bit_index)) + { + // Enough space + curr_bits_n = (uint8_t)bits_remain; + } + else + { + curr_bits_n = (8 - i_bit_index); + } + + // Pack these n bits into the current byte + // Mask out whatever was at that position with ones (xxx11111) + buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); + // Put content to this position, by masking out the non-used part + buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); + + // Increment the bit index + i_bit_index += curr_bits_n; + + // Now proceed to the next byte, if necessary + bits_remain -= curr_bits_n; + if (bits_remain > 0) + { + // Offer another 8 bits / one byte + i_byte_index++; + i_bit_index = 0; + } + } + + *r_bit_index = i_bit_index; + // If a partly filled byte is present, mark this as consumed + if (i_bit_index != 7) i_byte_index++; + return i_byte_index - packet_index; +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +// To make MAVLink work on your MCU, define comm_send_ch() if you wish +// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a +// whole packet at a time + +/* + +#include "mavlink_types.h" + +void comm_send_ch(mavlink_channel_t chan, uint8_t ch) +{ + if (chan == MAVLINK_COMM_0) + { + uart0_transmit(ch); + } + if (chan == MAVLINK_COMM_1) + { + uart1_transmit(ch); + } +} + */ + +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) +{ +#ifdef MAVLINK_SEND_UART_BYTES + /* this is the more efficient approach, if the platform + defines it */ + MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); +#else + /* fallback to one byte at a time */ + uint16_t i; + for (i = 0; i < len; i++) { + comm_send_ch(chan, (uint8_t)buf[i]); + } +#endif +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/pymavlink/generator/C/include_v1.0/mavlink_types.h b/pymavlink/generator/C/include_v1.0/mavlink_types.h new file mode 100644 index 0000000..0a98ccc --- /dev/null +++ b/pymavlink/generator/C/include_v1.0/mavlink_types.h @@ -0,0 +1,228 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +// Visual Studio versions before 2010 don't have stdint.h, so we just error out. +#if (defined _MSC_VER) && (_MSC_VER < 1600) +#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" +#endif + +#include + +// Macro to define packed structures +#ifdef __GNUC__ + #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed)) +#else + #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#endif + +#ifndef MAVLINK_MAX_PAYLOAD_LEN +// it is possible to override this, but be careful! +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length +#endif + +#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) +#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum +#define MAVLINK_NUM_CHECKSUM_BYTES 2 +#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length + +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 +#define MAVLINK_EXTENDED_HEADER_LEN 14 + +#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__) + /* full fledged 32bit++ OS */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 +#else + /* small microcontrollers */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 +#endif + +#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) + + +/** + * Old-style 4 byte param union + * + * This struct is the data format to be used when sending + * parameters. The parameter should be copied to the native + * type (without type conversion) + * and re-instanted on the receiving side using the + * native type as well. + */ +MAVPACKED( +typedef struct param_union { + union { + float param_float; + int32_t param_int32; + uint32_t param_uint32; + int16_t param_int16; + uint16_t param_uint16; + int8_t param_int8; + uint8_t param_uint8; + uint8_t bytes[4]; + }; + uint8_t type; +}) mavlink_param_union_t; + + +/** + * New-style 8 byte param union + * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. + * The mavlink_param_union_double_t will be treated as a little-endian structure. + * + * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. + * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the + * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. + * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, + * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86, + * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, + * and the bits pulled out using the shifts/masks. +*/ +MAVPACKED( +typedef struct param_union_extended { + union { + struct { + uint8_t is_double:1; + uint8_t mavlink_type:7; + union { + char c; + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; + float f; + uint8_t align[7]; + }; + }; + uint8_t data[8]; + }; +}) mavlink_param_union_double_t; + +/** + * This structure is required to make the mavlink_send_xxx convenience functions + * work, as it tells the library what the current system and component ID are. + */ +MAVPACKED( +typedef struct __mavlink_system { + uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function +}) mavlink_system_t; + +MAVPACKED( +typedef struct __mavlink_message { + uint16_t checksum; ///< sent at end of packet + uint8_t magic; ///< protocol magic marker + uint8_t len; ///< Length of payload + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint8_t msgid; ///< ID of message in payload + uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; +}) mavlink_message_t; + +MAVPACKED( +typedef struct __mavlink_extended_message { + mavlink_message_t base_msg; + int32_t extended_payload_len; ///< Length of extended payload if any + uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; +}) mavlink_extended_message_t; + +typedef enum { + MAVLINK_TYPE_CHAR = 0, + MAVLINK_TYPE_UINT8_T = 1, + MAVLINK_TYPE_INT8_T = 2, + MAVLINK_TYPE_UINT16_T = 3, + MAVLINK_TYPE_INT16_T = 4, + MAVLINK_TYPE_UINT32_T = 5, + MAVLINK_TYPE_INT32_T = 6, + MAVLINK_TYPE_UINT64_T = 7, + MAVLINK_TYPE_INT64_T = 8, + MAVLINK_TYPE_FLOAT = 9, + MAVLINK_TYPE_DOUBLE = 10 +} mavlink_message_type_t; + +#define MAVLINK_MAX_FIELDS 64 + +typedef struct __mavlink_field_info { + const char *name; // name of this field + const char *print_format; // printing format hint, or NULL + mavlink_message_type_t type; // type of this field + unsigned int array_length; // if non-zero, field is an array + unsigned int wire_offset; // offset of each field in the payload + unsigned int structure_offset; // offset in a C structure +} mavlink_field_info_t; + +// note that in this structure the order of fields is the order +// in the XML file, not necessary the wire order +typedef struct __mavlink_message_info { + const char *name; // name of the message + unsigned num_fields; // how many fields in this message + mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information +} mavlink_message_info_t; + +#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) +#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) + +// checksum is immediately after the payload bytes +#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) +#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_2, + MAVLINK_COMM_3 +} mavlink_channel_t; + +/* + * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number + * of buffers they will use. If more are used, then the result will be + * a stack overrun + */ +#ifndef MAVLINK_COMM_NUM_BUFFERS +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +# define MAVLINK_COMM_NUM_BUFFERS 16 +#else +# define MAVLINK_COMM_NUM_BUFFERS 4 +#endif +#endif + +typedef enum { + MAVLINK_PARSE_STATE_UNINIT=0, + MAVLINK_PARSE_STATE_IDLE, + MAVLINK_PARSE_STATE_GOT_STX, + MAVLINK_PARSE_STATE_GOT_SEQ, + MAVLINK_PARSE_STATE_GOT_LENGTH, + MAVLINK_PARSE_STATE_GOT_SYSID, + MAVLINK_PARSE_STATE_GOT_COMPID, + MAVLINK_PARSE_STATE_GOT_MSGID, + MAVLINK_PARSE_STATE_GOT_PAYLOAD, + MAVLINK_PARSE_STATE_GOT_CRC1, + MAVLINK_PARSE_STATE_GOT_BAD_CRC1 +} mavlink_parse_state_t; ///< The state machine for the comm parser + +typedef enum { + MAVLINK_FRAMING_INCOMPLETE=0, + MAVLINK_FRAMING_OK=1, + MAVLINK_FRAMING_BAD_CRC=2 +} mavlink_framing_t; + +typedef struct __mavlink_status { + uint8_t msg_received; ///< Number of received messages + uint8_t buffer_overrun; ///< Number of buffer overruns + uint8_t parse_error; ///< Number of parse errors + mavlink_parse_state_t parse_state; ///< Parsing state machine + uint8_t packet_idx; ///< Index in current packet + uint8_t current_rx_seq; ///< Sequence number of last packet received + uint8_t current_tx_seq; ///< Sequence number of last packet sent + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#define MAVLINK_BIG_ENDIAN 0 +#define MAVLINK_LITTLE_ENDIAN 1 + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/pymavlink/generator/C/include_v1.0/protocol.h b/pymavlink/generator/C/include_v1.0/protocol.h new file mode 100644 index 0000000..bf20708 --- /dev/null +++ b/pymavlink/generator/C/include_v1.0/protocol.h @@ -0,0 +1,339 @@ +#ifndef _MAVLINK_PROTOCOL_H_ +#define _MAVLINK_PROTOCOL_H_ + +#include "string.h" +#include "mavlink_types.h" + +/* + If you want MAVLink on a system that is native big-endian, + you need to define NATIVE_BIG_ENDIAN +*/ +#ifdef NATIVE_BIG_ENDIAN +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) +#else +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) +#endif + +#ifndef MAVLINK_STACK_BUFFER +#define MAVLINK_STACK_BUFFER 0 +#endif + +#ifndef MAVLINK_AVOID_GCC_STACK_BUG +# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) +#endif + +#ifndef MAVLINK_ASSERT +#define MAVLINK_ASSERT(x) +#endif + +#ifndef MAVLINK_START_UART_SEND +#define MAVLINK_START_UART_SEND(chan, length) +#endif + +#ifndef MAVLINK_END_UART_SEND +#define MAVLINK_END_UART_SEND(chan, length) +#endif + +/* option to provide alternative implementation of mavlink_helpers.h */ +#ifdef MAVLINK_SEPARATE_HELPERS + + #define MAVLINK_HELPER + + /* decls in sync with those in mavlink_helpers.h */ + #ifndef MAVLINK_GET_CHANNEL_STATUS + MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); + #endif + MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan); + #if MAVLINK_CRC_EXTRA + MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra); + MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra); + #endif + #else + MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length); + MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); + #endif + #endif // MAVLINK_CRC_EXTRA + MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); + MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); + MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); + MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, + mavlink_status_t* status, + uint8_t c, + mavlink_message_t* r_message, + mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, + uint8_t* r_bit_index, uint8_t* buffer); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg); + #endif + +#else + + #define MAVLINK_HELPER static inline + #include "mavlink_helpers.h" + +#endif // MAVLINK_SEPARATE_HELPERS + +/** + * @brief Get the required buffer size for this message + */ +static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) +{ + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + +#if MAVLINK_NEED_BYTE_SWAP +static inline void byte_swap_2(char *dst, const char *src) +{ + dst[0] = src[1]; + dst[1] = src[0]; +} +static inline void byte_swap_4(char *dst, const char *src) +{ + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; +} +static inline void byte_swap_8(char *dst, const char *src) +{ + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; +} +#elif !MAVLINK_ALIGNED_FIELDS +static inline void byte_copy_2(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; +} +static inline void byte_copy_4(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + dst[3] = src[3]; +} +static inline void byte_copy_8(char *dst, const char *src) +{ + memcpy(dst, src, 8); +} +#endif + +#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b +#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b +#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b + +#if MAVLINK_NEED_BYTE_SWAP +#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#elif !MAVLINK_ALIGNED_FIELDS +#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#else +#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b +#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b +#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b +#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b +#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b +#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b +#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b +#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b +#endif + +/* + like memcpy(), but if src is NULL, do a memset to zero +*/ +static inline void mav_array_memcpy(void *dest, const void *src, size_t n) +{ + if (src == NULL) { + memset(dest, 0, n); + } else { + memcpy(dest, src, n); + } +} + +/* + * Place a char array into a buffer + */ +static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a uint8_t array into a buffer + */ +static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a int8_t array into a buffer + */ +static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +#if MAVLINK_NEED_BYTE_SWAP +#define _MAV_PUT_ARRAY(TYPE, V) \ +static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ +{ \ + if (b == NULL) { \ + memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ + } else { \ + uint16_t i; \ + for (i=0; imsgid = MAVLINK_MSG_ID_TEST_TYPES; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +} + +/** + * @brief Pack a test_types message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TEST_TYPES_LEN]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +} + +/** + * @brief Encode a test_types struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param test_types C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) +{ + return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); +} + +/** + * @brief Send a test_types message + * @param chan MAVLink channel to send the message + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TEST_TYPES_LEN]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); + mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); + mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet.s, s, sizeof(char)*10); + mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, MAVLINK_MSG_ID_TEST_TYPES_LEN, MAVLINK_MSG_ID_TEST_TYPES_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +#endif +} + +#endif + +// MESSAGE TEST_TYPES UNPACKING + + +/** + * @brief Get field c from test_types message + * + * @return char + */ +static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_char(msg, 160); +} + +/** + * @brief Get field s from test_types message + * + * @return string + */ +static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) +{ + return _MAV_RETURN_char_array(msg, s, 10, 161); +} + +/** + * @brief Get field u8 from test_types message + * + * @return uint8_t + */ +static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 171); +} + +/** + * @brief Get field u16 from test_types message + * + * @return uint16_t + */ +static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 144); +} + +/** + * @brief Get field u32 from test_types message + * + * @return uint32_t + */ +static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 96); +} + +/** + * @brief Get field u64 from test_types message + * + * @return uint64_t + */ +static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field s8 from test_types message + * + * @return int8_t + */ +static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 172); +} + +/** + * @brief Get field s16 from test_types message + * + * @return int16_t + */ +static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 146); +} + +/** + * @brief Get field s32 from test_types message + * + * @return int32_t + */ +static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 100); +} + +/** + * @brief Get field s64 from test_types message + * + * @return int64_t + */ +static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 8); +} + +/** + * @brief Get field f from test_types message + * + * @return float + */ +static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 104); +} + +/** + * @brief Get field d from test_types message + * + * @return double + */ +static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) +{ + return _MAV_RETURN_double(msg, 16); +} + +/** + * @brief Get field u8_array from test_types message + * + * @return uint8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) +{ + return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 173); +} + +/** + * @brief Get field u16_array from test_types message + * + * @return uint16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) +{ + return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 148); +} + +/** + * @brief Get field u32_array from test_types message + * + * @return uint32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) +{ + return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 108); +} + +/** + * @brief Get field u64_array from test_types message + * + * @return uint64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) +{ + return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 24); +} + +/** + * @brief Get field s8_array from test_types message + * + * @return int8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) +{ + return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 176); +} + +/** + * @brief Get field s16_array from test_types message + * + * @return int16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) +{ + return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 154); +} + +/** + * @brief Get field s32_array from test_types message + * + * @return int32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) +{ + return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 120); +} + +/** + * @brief Get field s64_array from test_types message + * + * @return int64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) +{ + return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 48); +} + +/** + * @brief Get field f_array from test_types message + * + * @return float_array + */ +static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) +{ + return _MAV_RETURN_float_array(msg, f_array, 3, 132); +} + +/** + * @brief Get field d_array from test_types message + * + * @return double_array + */ +static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) +{ + return _MAV_RETURN_double_array(msg, d_array, 3, 72); +} + +/** + * @brief Decode a test_types message into a struct + * + * @param msg The message to decode + * @param test_types C-struct to decode the message contents into + */ +static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) +{ +#if MAVLINK_NEED_BYTE_SWAP + test_types->u64 = mavlink_msg_test_types_get_u64(msg); + test_types->s64 = mavlink_msg_test_types_get_s64(msg); + test_types->d = mavlink_msg_test_types_get_d(msg); + mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); + mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); + mavlink_msg_test_types_get_d_array(msg, test_types->d_array); + test_types->u32 = mavlink_msg_test_types_get_u32(msg); + test_types->s32 = mavlink_msg_test_types_get_s32(msg); + test_types->f = mavlink_msg_test_types_get_f(msg); + mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); + mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); + mavlink_msg_test_types_get_f_array(msg, test_types->f_array); + test_types->u16 = mavlink_msg_test_types_get_u16(msg); + test_types->s16 = mavlink_msg_test_types_get_s16(msg); + mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); + mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); + test_types->c = mavlink_msg_test_types_get_c(msg); + mavlink_msg_test_types_get_s(msg, test_types->s); + test_types->u8 = mavlink_msg_test_types_get_u8(msg); + test_types->s8 = mavlink_msg_test_types_get_s8(msg); + mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); + mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); +#else + memcpy(test_types, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TEST_TYPES_LEN); +#endif +} diff --git a/pymavlink/generator/C/include_v1.0/test/test.h b/pymavlink/generator/C/include_v1.0/test/test.h new file mode 100644 index 0000000..06192f0 --- /dev/null +++ b/pymavlink/generator/C/include_v1.0/test/test.h @@ -0,0 +1,53 @@ +/** @file + * @brief MAVLink comm protocol generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_H +#define TEST_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_TEST + +// ENUM DEFINITIONS + + + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_test_types.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // TEST_H diff --git a/pymavlink/generator/C/include_v1.0/test/testsuite.h b/pymavlink/generator/C/include_v1.0/test/testsuite.h new file mode 100644 index 0000000..658e1ae --- /dev/null +++ b/pymavlink/generator/C/include_v1.0/test/testsuite.h @@ -0,0 +1,120 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_TESTSUITE_H +#define TEST_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_test(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_test_types_t packet_in = { + 93372036854775807ULL, + 93372036854776311LL, + 235.0, + { 93372036854777319, 93372036854777320, 93372036854777321 }, + { 93372036854778831, 93372036854778832, 93372036854778833 }, + { 627.0, 628.0, 629.0 }, + 963502456, + 963502664, + 745.0, + { 963503080, 963503081, 963503082 }, + { 963503704, 963503705, 963503706 }, + { 941.0, 942.0, 943.0 }, + 24723, + 24827, + { 24931, 24932, 24933 }, + { 25243, 25244, 25245 }, + 'E', + "FGHIJKLMN", + 198, + 9, + { 76, 77, 78 }, + { 21, 22, 23 }, + }; + mavlink_test_types_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.u64 = packet_in.u64; + packet1.s64 = packet_in.s64; + packet1.d = packet_in.d; + packet1.u32 = packet_in.u32; + packet1.s32 = packet_in.s32; + packet1.f = packet_in.f; + packet1.u16 = packet_in.u16; + packet1.s16 = packet_in.s16; + packet1.c = packet_in.c; + packet1.u8 = packet_in.u8; + packet1.s8 = packet_in.s8; + + mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); + mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); + mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); + mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); + mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); + mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); + mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); + mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); + mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10); + mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); + mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i +#include +#include +#include +#include + +#define MAVLINK_USE_CONVENIENCE_FUNCTIONS +#define MAVLINK_COMM_NUM_BUFFERS 2 + +// this trick allows us to make mavlink_message_t as small as possible +// for this dialect, which saves some memory +#include +#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE + +#include +static mavlink_system_t mavlink_system = {42,11,}; + +#define MAVLINK_ASSERT(x) assert(x) +static void comm_send_ch(mavlink_channel_t chan, uint8_t c); + +static mavlink_message_t last_msg; + +#include +#include + +static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; + +static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; +static unsigned error_count; + +static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; + +static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) +{ +#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) + switch (f->type) { + case MAVLINK_TYPE_CHAR: + printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1)); + break; + case MAVLINK_TYPE_UINT8_T: + printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1)); + break; + case MAVLINK_TYPE_INT8_T: + printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1)); + break; + case MAVLINK_TYPE_UINT16_T: + printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2)); + break; + case MAVLINK_TYPE_INT16_T: + printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2)); + break; + case MAVLINK_TYPE_UINT32_T: + printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4)); + break; + case MAVLINK_TYPE_INT32_T: + printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4)); + break; + case MAVLINK_TYPE_UINT64_T: + printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8)); + break; + case MAVLINK_TYPE_INT64_T: + printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8)); + break; + case MAVLINK_TYPE_FLOAT: + printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4)); + break; + case MAVLINK_TYPE_DOUBLE: + printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8)); + break; + } +} + +static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f) +{ + printf("%s: ", f->name); + if (f->array_length == 0) { + print_one_field(msg, f, 0); + printf(" "); + } else { + unsigned i; + /* print an array */ + if (f->type == MAVLINK_TYPE_CHAR) { + printf("'%.*s'", f->array_length, + f->wire_offset+(const char *)_MAV_PAYLOAD(msg)); + + } else { + printf("[ "); + for (i=0; iarray_length; i++) { + print_one_field(msg, f, i); + if (i < f->array_length) { + printf(", "); + } + } + printf("]"); + } + } + printf(" "); +} + +static void print_message(mavlink_message_t *msg) +{ + const mavlink_message_info_t *m = &message_info[msg->msgid]; + const mavlink_field_info_t *f = m->fields; + unsigned i; + printf("%s { ", m->name); + for (i=0; inum_fields; i++) { + print_field(msg, &f[i]); + } + printf("}\n"); +} + +static void comm_send_ch(mavlink_channel_t chan, uint8_t c) +{ + mavlink_status_t status; + if (mavlink_parse_char(chan, c, &last_msg, &status)) { + print_message(&last_msg); + chan_counts[chan]++; + /* channel 0 gets 3 messages per message, because of + the channel defaults for _pack() and _encode() */ + if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) { + printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n", + chan_counts[chan], status.current_rx_seq); + error_count++; + } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) { + printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n", + (unsigned)chan, chan_counts[chan], status.current_rx_seq); + error_count++; + } + if (message_lengths[last_msg.msgid] != last_msg.len) { + printf("Incorrect message length %u for message %u - expected %u\n", + (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]); + error_count++; + } + } + if (status.packet_rx_drop_count != 0) { + printf("Parse error at packet %u\n", chan_counts[chan]); + error_count++; + } +} + +int main(void) +{ + mavlink_channel_t chan; + mavlink_test_all(11, 10, &last_msg); + for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) { + printf("Received %u messages on channel %u OK\n", + chan_counts[chan], (unsigned)chan); + } + if (error_count != 0) { + printf("Error count %u\n", error_count); + exit(1); + } + printf("No errors detected\n"); + return 0; +} + diff --git a/pymavlink/generator/C/test/windows/stdafx.cpp b/pymavlink/generator/C/test/windows/stdafx.cpp new file mode 100644 index 0000000..98b4abf --- /dev/null +++ b/pymavlink/generator/C/test/windows/stdafx.cpp @@ -0,0 +1,8 @@ +// stdafx.cpp : source file that includes just the standard includes +// testmav.pch will be the pre-compiled header +// stdafx.obj will contain the pre-compiled type information + +#include "stdafx.h" + +// TODO: reference any additional headers you need in STDAFX.H +// and not in this file diff --git a/pymavlink/generator/C/test/windows/stdafx.h b/pymavlink/generator/C/test/windows/stdafx.h new file mode 100644 index 0000000..47a0d02 --- /dev/null +++ b/pymavlink/generator/C/test/windows/stdafx.h @@ -0,0 +1,15 @@ +// stdafx.h : include file for standard system include files, +// or project specific include files that are used frequently, but +// are changed infrequently +// + +#pragma once + +#include "targetver.h" + +#include +#include + + + +// TODO: reference additional headers your program requires here diff --git a/pymavlink/generator/C/test/windows/targetver.h b/pymavlink/generator/C/test/windows/targetver.h new file mode 100644 index 0000000..90e767b --- /dev/null +++ b/pymavlink/generator/C/test/windows/targetver.h @@ -0,0 +1,8 @@ +#pragma once + +// Including SDKDDKVer.h defines the highest available Windows platform. + +// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and +// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. + +#include diff --git a/pymavlink/generator/C/test/windows/testmav.cpp b/pymavlink/generator/C/test/windows/testmav.cpp new file mode 100644 index 0000000..aa83cac --- /dev/null +++ b/pymavlink/generator/C/test/windows/testmav.cpp @@ -0,0 +1,154 @@ +// testmav.cpp : Defines the entry point for the console application. +// + +#include "stdafx.h" +#include "stdio.h" +#include "stdint.h" +#include "stddef.h" +#include "assert.h" + + +#define MAVLINK_USE_CONVENIENCE_FUNCTIONS +#define MAVLINK_COMM_NUM_BUFFERS 2 + +#include +static mavlink_system_t mavlink_system = {42,11,}; + +#define MAVLINK_ASSERT(x) assert(x) +static void comm_send_ch(mavlink_channel_t chan, uint8_t c); + +static mavlink_message_t last_msg; + +#include +#include + +static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; + +static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; +static unsigned error_count; + +static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; + +static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) +{ +#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) + switch (f->type) { + case MAVLINK_TYPE_CHAR: + printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1)); + break; + case MAVLINK_TYPE_UINT8_T: + printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1)); + break; + case MAVLINK_TYPE_INT8_T: + printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1)); + break; + case MAVLINK_TYPE_UINT16_T: + printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2)); + break; + case MAVLINK_TYPE_INT16_T: + printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2)); + break; + case MAVLINK_TYPE_UINT32_T: + printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4)); + break; + case MAVLINK_TYPE_INT32_T: + printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4)); + break; + case MAVLINK_TYPE_UINT64_T: + printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8)); + break; + case MAVLINK_TYPE_INT64_T: + printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8)); + break; + case MAVLINK_TYPE_FLOAT: + printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4)); + break; + case MAVLINK_TYPE_DOUBLE: + printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8)); + break; + } +} + +static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f) +{ + printf("%s: ", f->name); + if (f->array_length == 0) { + print_one_field(msg, f, 0); + printf(" "); + } else { + unsigned i; + /* print an array */ + if (f->type == MAVLINK_TYPE_CHAR) { + printf("'%.*s'", f->array_length, + f->wire_offset+(const char *)_MAV_PAYLOAD(msg)); + + } else { + printf("[ "); + for (i=0; iarray_length; i++) { + print_one_field(msg, f, i); + if (i < f->array_length) { + printf(", "); + } + } + printf("]"); + } + } + printf(" "); +} + +static void print_message(mavlink_message_t *msg) +{ + const mavlink_message_info_t *m = &message_info[msg->msgid]; + const mavlink_field_info_t *f = m->fields; + unsigned i; + printf("%s { ", m->name); + for (i=0; inum_fields; i++) { + print_field(msg, &f[i]); + } + printf("}\n"); +} + +static void comm_send_ch(mavlink_channel_t chan, uint8_t c) +{ + mavlink_status_t status; + if (mavlink_parse_char(chan, c, &last_msg, &status)) { + print_message(&last_msg); + chan_counts[chan]++; + /* channel 0 gets 3 messages per message, because of + the channel defaults for _pack() and _encode() */ + if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) { + printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n", + chan_counts[chan], status.current_rx_seq); + error_count++; + } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) { + printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n", + (unsigned)chan, chan_counts[chan], status.current_rx_seq); + error_count++; + } + if (message_lengths[last_msg.msgid] != last_msg.len) { + printf("Incorrect message length %u for message %u - expected %u\n", + (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]); + error_count++; + } + } + if (status.packet_rx_drop_count != 0) { + printf("Parse error at packet %u\n", chan_counts[chan]); + error_count++; + } +} + +int _tmain(int argc, _TCHAR* argv[]) +{ + int chan; + mavlink_test_all(11, 10, &last_msg); + for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) { + printf("Received %u messages on channel %u OK\n", + chan_counts[chan], (unsigned)chan); + } + if (error_count != 0) { + printf("Error count %u\n", error_count); + return(1); + } + printf("No errors detected\n"); + return 0; +} diff --git a/pymavlink/generator/C/test/windows/testmav.sln b/pymavlink/generator/C/test/windows/testmav.sln new file mode 100644 index 0000000..37a3056 --- /dev/null +++ b/pymavlink/generator/C/test/windows/testmav.sln @@ -0,0 +1,20 @@ + +Microsoft Visual Studio Solution File, Format Version 11.00 +# Visual C++ Express 2010 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "testmav", "testmav\testmav.vcxproj", "{02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|Win32 = Debug|Win32 + Release|Win32 = Release|Win32 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Debug|Win32.ActiveCfg = Debug|Win32 + {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Debug|Win32.Build.0 = Debug|Win32 + {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Release|Win32.ActiveCfg = Release|Win32 + {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F}.Release|Win32.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/pymavlink/generator/C/test/windows/testmav.suo b/pymavlink/generator/C/test/windows/testmav.suo new file mode 100644 index 0000000..9b2e18c Binary files /dev/null and b/pymavlink/generator/C/test/windows/testmav.suo differ diff --git a/pymavlink/generator/C/test/windows/testmav.vcxproj b/pymavlink/generator/C/test/windows/testmav.vcxproj new file mode 100644 index 0000000..7181b3a --- /dev/null +++ b/pymavlink/generator/C/test/windows/testmav.vcxproj @@ -0,0 +1,91 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + + {02C30EBC-DF41-4C36-B2F3-79BED7E6EF9F} + Win32Proj + testmav + + + + Application + true + Unicode + + + Application + false + true + Unicode + + + + + + + + + + + + + true + + + false + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + E:\pymavlink\generator\C\include_v1.0 + + + Console + true + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + + Console + true + true + true + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/pymavlink/generator/CS/common/ByteArrayUtil.cs b/pymavlink/generator/CS/common/ByteArrayUtil.cs new file mode 100644 index 0000000..2fa246e --- /dev/null +++ b/pymavlink/generator/CS/common/ByteArrayUtil.cs @@ -0,0 +1,198 @@ +using System; +using System.Text; + +namespace MavLink +{ + internal static class ByteArrayUtil + { +#if MF_FRAMEWORK_VERSION_V4_1 + private static readonly MavBitConverter bitConverter = new MavBitConverter(); +#else + private static readonly FrameworkBitConverter bitConverter = new FrameworkBitConverter(); +#endif + + public static byte[] ToChar(byte[] source, int sourceOffset, int size) + { + var bytes = new byte[size]; + + for (int i = 0; i < size; i++) + bytes[i] = source[i + sourceOffset]; + + return bytes; + } + + public static byte[] ToUInt8(byte[] source, int sourceOffset, int size) + { + var bytes = new byte[size]; + Array.Copy(source, sourceOffset, bytes, 0, size); + return bytes; + } + + public static sbyte[] ToInt8(byte[] source, int sourceOffset, int size) + { + var bytes = new sbyte[size]; + + for (int i = 0; i < size; i++) + bytes[i] = unchecked((sbyte)source[i + sourceOffset]); + + return bytes; + } + + public static UInt16[] ToUInt16(byte[] source, int sourceOffset, int size) + { + var arr = new UInt16[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToUInt16(source, sourceOffset + (i * sizeof (UInt16))); + return arr; + } + + public static Int16[] ToInt16(byte[] source, int sourceOffset, int size) + { + var arr = new Int16[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToInt16(source, sourceOffset + (i * sizeof(Int16))); + return arr; + } + + public static UInt32[] ToUInt32(byte[] source, int sourceOffset, int size) + { + var arr = new UInt32[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToUInt16(source, sourceOffset + (i * sizeof(UInt32))); + return arr; + } + + public static Int32[] ToInt32(byte[] source, int sourceOffset, int size) + { + var arr = new Int32[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToInt16(source, sourceOffset + (i * sizeof(Int32))); + return arr; + } + + public static UInt64[] ToUInt64(byte[] source, int sourceOffset, int size) + { + var arr = new UInt64[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToUInt16(source, sourceOffset + (i * sizeof(UInt64))); + return arr; + } + + public static Int64[] ToInt64(byte[] source, int sourceOffset, int size) + { + var arr = new Int64[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToInt16(source, sourceOffset + (i * sizeof(Int64))); + return arr; + } + + public static Single[] ToSingle(byte[] source, int sourceOffset, int size) + { + var arr = new Single[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToUInt16(source, sourceOffset + (i * sizeof(Single))); + return arr; + } + + public static Double[] ToDouble(byte[] source, int sourceOffset, int size) + { + var arr = new Double[size]; + for (int i = 0; i < size; i++) + arr[i] = bitConverter.ToInt16(source, sourceOffset + (i * sizeof(Double))); + return arr; + } + + public static void ToByteArray(byte[] src, byte[] dst, int offset, int size) + { + int i; + for (i = 0; i < src.Length; i++) + dst[offset + i] = src[i]; + while (i++ < size) + dst[offset + i] = 0; + } + + public static void ToByteArray(sbyte[] src, byte[] dst, int offset, int size) + { + int i; + for (i = 0; i < size && i + /// converter from byte[] => primitive CLR types + /// delegates to the .Net framework bitconverter for speed, and to avoid using unsafe pointer + /// casting for Silverlight. + /// + internal class FrameworkBitConverter + { + private bool _shouldReverse = false; + + public void SetDataIsLittleEndian(bool islittle) + { + _shouldReverse = islittle == !BitConverter.IsLittleEndian; + } + + public UInt16 ToUInt16(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new[] {value[startIndex + 1], value[startIndex]}; + return BitConverter.ToUInt16(bytes,0); + } + return BitConverter.ToUInt16(value, startIndex); + } + + public Int16 ToInt16(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new[] { value[startIndex + 1], value[startIndex] }; + return BitConverter.ToInt16(bytes, 0); + } + return BitConverter.ToInt16(value, startIndex); + } + + public sbyte ToInt8(byte[] value, int startIndex) + { + return unchecked((sbyte)value[startIndex]); + } + + public Int32 ToInt32(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new byte[4]; + Array.Copy(value,startIndex,bytes,0,4); + Array.Reverse(bytes); + return BitConverter.ToInt32(bytes, 0); + } + return BitConverter.ToInt32(value, startIndex); + } + + public UInt32 ToUInt32(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new byte[4]; + Array.Copy(value, startIndex, bytes, 0, 4); + Array.Reverse(bytes); + return BitConverter.ToUInt32(bytes, 0); + } + return BitConverter.ToUInt32(value, startIndex); + } + + public UInt64 ToUInt64(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new byte[8]; + Array.Copy(value, startIndex, bytes, 0, bytes.Length); + Array.Reverse(bytes); + return BitConverter.ToUInt64(bytes, 0); + } + return BitConverter.ToUInt64(value, startIndex); + } + + public Int64 ToInt64(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new byte[8]; + Array.Copy(value, startIndex, bytes, 0, bytes.Length); + Array.Reverse(bytes); + return BitConverter.ToInt64(bytes, 0); + } + return BitConverter.ToInt64(value, startIndex); + } + + public Single ToSingle(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new byte[4]; + Array.Copy(value, startIndex, bytes, 0, bytes.Length); + Array.Reverse(bytes); + return BitConverter.ToSingle(bytes, 0); + } + return BitConverter.ToSingle(value, startIndex); + } + + public Double ToDouble(byte[] value, int startIndex) + { + if (_shouldReverse) + { + var bytes = new byte[8]; + Array.Copy(value, startIndex, bytes, 0, bytes.Length); + Array.Reverse(bytes); + return BitConverter.ToDouble(bytes, 0); + } + return BitConverter.ToDouble(value, startIndex); + } + + public void GetBytes(Double value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + Array.Copy(bytes, 0, dst, offset, bytes.Length); + + } + + public void GetBytes(Single value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public void GetBytes(UInt64 value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public void GetBytes(Int64 value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public void GetBytes(UInt32 value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public void GetBytes(Int16 value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public void GetBytes(Int32 value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public void GetBytes(UInt16 value, byte[] dst, int offset) + { + var bytes = BitConverter.GetBytes(value); + if (_shouldReverse) Array.Reverse(bytes); + + Array.Copy(bytes, 0, dst, offset, bytes.Length); + } + + public byte[] GetBytes(sbyte value) + { + return new byte[1] + { + (byte)value, + }; + } + } +} \ No newline at end of file diff --git a/pymavlink/generator/CS/common/Mavlink.cs b/pymavlink/generator/CS/common/Mavlink.cs new file mode 100644 index 0000000..299728d --- /dev/null +++ b/pymavlink/generator/CS/common/Mavlink.cs @@ -0,0 +1,437 @@ +using System; +using MavLink; + +namespace MavLink +{ + /// + /// Mavlink communication class. + /// + /// + /// Keeps track of state across send and receive of packets. + /// User of this class can just send Mavlink Messsages, and + /// receive them by feeding this class bytes off the wire as + /// they arrive + /// + public class Mavlink + { + private byte[] leftovers; + + /// + /// Event raised when a message is decoded successfully + /// + public event PacketReceivedEventHandler PacketReceived; + + /// + /// Total number of packets successfully received so far + /// + public UInt32 PacketsReceived { get; private set; } + + /// + /// Total number of packets which have been rejected due to a failed crc + /// + public UInt32 BadCrcPacketsReceived { get; private set; } + + /// + /// Raised when a packet does not pass CRC + /// + public event PacketCRCFailEventHandler PacketFailedCRC; + + /// + /// Raised when a number of bytes are passed over and cannot + /// be used to decode a packet + /// + public event PacketCRCFailEventHandler BytesUnused; + + // The current packet sequence number for transmission + // public so it can be manipulated for testing + // Normal usage would only read this + public byte txPacketSequence; + + /// + /// Create a new MavlinkLink Object + /// + public Mavlink() + { + MavLinkSerializer.SetDataIsLittleEndian(MavlinkSettings.IsLittleEndian); + leftovers = new byte[] {}; + } + + + /// + /// Process latest bytes from the stream. Received packets will be raised in the event + /// + public void ParseBytes(byte[] newlyReceived) + { + uint i = 0; + + // copy the old and new into a contiguous array + // This is pretty inefficient... + var bytesToProcess = new byte[newlyReceived.Length + leftovers.Length]; + int j = 0; + + for (i = 0; i < leftovers.Length; i++) + bytesToProcess[j++] = leftovers[i]; + + for (i = 0; i < newlyReceived.Length; i++) + bytesToProcess[j++] = newlyReceived[i]; + + i = 0; + + // we are going to loop and decode packets until we use up the data + // at which point we will return. Hence one call to this method could + // result in multiple packet decode events + while (true) + { + // Hunt for the start char + int huntStartPos = (int)i; + + while (i < bytesToProcess.Length && bytesToProcess[i] != MavlinkSettings.ProtocolMarker) + i++; + + if (i == bytesToProcess.Length) + { + // No start byte found in all our bytes. Dump them, Exit. + leftovers = new byte[] { }; + return; + } + + if (i > huntStartPos) + { + // if we get here then are some bytes which this code thinks are + // not interesting and would be dumped. For diagnostics purposes, + // lets pop these bytes up in an event. + if (BytesUnused != null) + { + var badBytes = new byte[i - huntStartPos]; + Array.Copy(bytesToProcess, huntStartPos, badBytes, 0, (int)(i - huntStartPos)); + BytesUnused(this, new PacketCRCFailEventArgs(badBytes, bytesToProcess.Length - huntStartPos)); + } + } + + // We need at least the minimum length of a packet to process it. + // The minimum packet length is 8 bytes for acknowledgement packets without payload + // if we don't have the minimum now, go round again + if (bytesToProcess.Length - i < 8) + { + leftovers = new byte[bytesToProcess.Length - i]; + j = 0; + while (i < bytesToProcess.Length) + leftovers[j++] = bytesToProcess[i++]; + return; + } + + /* + * Byte order: + * + * 0 Packet start sign + * 1 Payload length 0 - 255 + * 2 Packet sequence 0 - 255 + * 3 System ID 1 - 255 + * 4 Component ID 0 - 255 + * 5 Message ID 0 - 255 + * 6 to (n+6) Data (0 - 255) bytes + * (n+7) to (n+8) Checksum (high byte, low byte) for v0.9, lowbyte, highbyte for 1.0 + * + */ + UInt16 payLoadLength = bytesToProcess[i + 1]; + + // Now we know the packet length, + // If we don't have enough bytes in this packet to satisfy that packet lenghth, + // then dump the whole lot in the leftovers and do nothing else - go round again + if (payLoadLength > (bytesToProcess.Length - i - 8)) // payload + 'overhead' bytes (crc, system etc) + { + // back up to the start char for next cycle + j = 0; + + leftovers = new byte[bytesToProcess.Length - i]; + + for (; i < bytesToProcess.Length; i++) + { + leftovers[j++] = bytesToProcess[i]; + } + return; + } + + i++; + + // Check the CRC. Does not include the starting 'U' byte but does include the length + var crc1 = Mavlink_Crc.Calculate(bytesToProcess, (UInt16)(i), (UInt16)(payLoadLength + 5)); + + if (MavlinkSettings.CrcExtra) + { + var possibleMsgId = bytesToProcess[i + 4]; + + if (!MavLinkSerializer.Lookup.ContainsKey(possibleMsgId)) + { + // we have received an unknown message. In this case we don't know the special + // CRC extra, so we have no choice but to fail. + + // The way we do this is to just let the procedure continue + // There will be a natural failure of the main packet CRC + } + else + { + var extra = MavLinkSerializer.Lookup[possibleMsgId]; + crc1 = Mavlink_Crc.CrcAccumulate(extra.CrcExtra, crc1); + } + } + + byte crcHigh = (byte)(crc1 & 0xFF); + byte crcLow = (byte)(crc1 >> 8); + + byte messageCrcHigh = bytesToProcess[i + 5 + payLoadLength]; + byte messageCrcLow = bytesToProcess[i + 6 + payLoadLength]; + + if (messageCrcHigh == crcHigh && messageCrcLow == crcLow) + { + // This is used for data drop outs metrics, not packet windows + // so we should consider this here. + // We pass up to subscribers only as an advisory thing + var rxPacketSequence = bytesToProcess[++i]; + i++; + var packet = new byte[payLoadLength + 3]; // +3 because we are going to send up the sys and comp id and msg type with the data + + for (j = 0; j < packet.Length; j++) + packet[j] = bytesToProcess[i + j]; + + var debugArray = new byte[payLoadLength + 7]; + Array.Copy(bytesToProcess, (int)(i - 3), debugArray, 0, debugArray.Length); + + //OnPacketDecoded(packet, rxPacketSequence, debugArray); + + ProcessPacketBytes(packet, rxPacketSequence); + + PacketsReceived++; + + // clear leftovers, just incase this is the last packet + leftovers = new byte[] { }; + + // advance i here by j to avoid unecessary hunting + // todo: could advance by j + 2 I think? + i = i + (uint)(j + 2); + } + else + { + var badBytes = new byte[i + 7 + payLoadLength]; + Array.Copy(bytesToProcess, (int)(i - 1), badBytes, 0, payLoadLength + 7); + + if (PacketFailedCRC != null) + { + PacketFailedCRC(this, new PacketCRCFailEventArgs(badBytes, (int)(bytesToProcess.Length - i - 1))); + } + + BadCrcPacketsReceived++; + } + } + } + + public byte[] Send(MavlinkPacket mavlinkPacket) + { + var bytes = this.Serialize(mavlinkPacket.Message, mavlinkPacket.SystemId, mavlinkPacket.ComponentId); + return SendPacketLinkLayer(bytes); + } + + // Send a raw message over the link - + // this will add start byte, lenghth, crc and other link layer stuff + private byte[] SendPacketLinkLayer(byte[] packetData) + { + /* + * Byte order: + * + * 0 Packet start sign + * 1 Payload length 0 - 255 + * 2 Packet sequence 0 - 255 + * 3 System ID 1 - 255 + * 4 Component ID 0 - 255 + * 5 Message ID 0 - 255 + * 6 to (n+6) Data (0 - 255) bytes + * (n+7) to (n+8) Checksum (high byte, low byte) + * + */ + var outBytes = new byte[packetData.Length + 5]; + + outBytes[0] = MavlinkSettings.ProtocolMarker; + outBytes[1] = (byte)(packetData.Length-3); // 3 bytes for sequence, id, msg type which this + // layer does not concern itself with + outBytes[2] = unchecked(txPacketSequence++); + + int i; + + for ( i = 0; i < packetData.Length; i++) + { + outBytes[i + 3] = packetData[i]; + } + + // Check the CRC. Does not include the starting byte but does include the length + var crc1 = Mavlink_Crc.Calculate(outBytes, 1, (UInt16)(packetData.Length + 2)); + + if (MavlinkSettings.CrcExtra) + { + var possibleMsgId = outBytes[5]; + var extra = MavLinkSerializer.Lookup[possibleMsgId]; + crc1 = Mavlink_Crc.CrcAccumulate(extra.CrcExtra, crc1); + } + + byte crc_high = (byte)(crc1 & 0xFF); + byte crc_low = (byte)(crc1 >> 8); + + outBytes[i + 3] = crc_high; + outBytes[i + 4] = crc_low; + + return outBytes; + } + + + // Process a raw packet in it's entirety in the given byte array + // if deserialization is successful, then the packetdecoded event will be raised + private void ProcessPacketBytes(byte[] packetBytes, byte rxPacketSequence) + { + // System ID 1 - 255 + // Component ID 0 - 255 + // Message ID 0 - 255 + // 6 to (n+6) Data (0 - 255) bytes + var packet = new MavlinkPacket + { + SystemId = packetBytes[0], + ComponentId = packetBytes[1], + SequenceNumber = rxPacketSequence, + Message = this.Deserialize(packetBytes, 2) + }; + + if (PacketReceived != null) + { + PacketReceived(this, packet); + } + + // else do what? + } + + + public MavlinkMessage Deserialize(byte[] bytes, int offset) + { + // first byte is the mavlink + var packetNum = (int)bytes[offset + 0]; + var packetGen = MavLinkSerializer.Lookup[packetNum].Deserializer; + return packetGen.Invoke(bytes, offset + 1); + } + + public byte[] Serialize(MavlinkMessage message, int systemId, int componentId) + { + var buff = new byte[256]; + + buff[0] = (byte)systemId; + buff[1] = (byte)componentId; + + var endPos = 3; + + var msgId = message.Serialize(buff, ref endPos); + + buff[2] = (byte)msgId; + + var resultBytes = new byte[endPos]; + Array.Copy(buff, resultBytes, endPos); + + return resultBytes; + } + } + + + /// + /// Describes an occurance when a packet fails CRC + /// + public class PacketCRCFailEventArgs : EventArgs + { + /// + /// + public PacketCRCFailEventArgs(byte[] badPacket, int offset) + { + BadPacket = badPacket; + Offset = offset; + } + + /// + /// The bytes that filed the CRC, including the starting character + /// + public byte[] BadPacket; + + /// + /// The offset in bytes where the start of the block begins, e.g + /// 50 would mean the block of badbytes would start 50 bytes ago + /// in the stread. No negative sign is necessary + /// + public int Offset; + } + + /// + /// Handler for an PacketFailedCRC Event + /// + public delegate void PacketCRCFailEventHandler(object sender, PacketCRCFailEventArgs e); + + + public delegate void PacketReceivedEventHandler(object sender, MavlinkPacket e); + + + /// + /// Represents a Mavlink message - both the message object itself + /// and the identified sending party + /// + public class MavlinkPacket + { + /// + /// The sender's system ID + /// + public int SystemId; + + /// + /// The sender's component ID + /// + public int ComponentId; + + /// + /// The sequence number received for this packet + /// + public byte SequenceNumber; + + + /// + /// Time of receipt + /// + public DateTime TimeStamp; + + /// + /// Object which is the mavlink message + /// + public MavlinkMessage Message; + } + + /// + /// Crc code copied/adapted from ardumega planner code + /// + internal static class Mavlink_Crc + { + const UInt16 X25_INIT_CRC = 0xffff; + + public static UInt16 CrcAccumulate(byte b, UInt16 crc) + { + unchecked + { + byte ch = (byte)(b ^ (byte)(crc & 0x00ff)); + ch = (byte)(ch ^ (ch << 4)); + return (UInt16)((crc >> 8) ^ (ch << 8) ^ (ch << 3) ^ (ch >> 4)); + } + } + + + // For a "message" of length bytes contained in the byte array + // pointed to by buffer, calculate the CRC + public static UInt16 Calculate(byte[] buffer, UInt16 start, UInt16 length) + { + UInt16 crcTmp = X25_INIT_CRC; + + for (int i = start; i < start + length; i++) + crcTmp = CrcAccumulate(buffer[i], crcTmp); + + return crcTmp; + } + } +} diff --git a/pymavlink/generator/__init__.py b/pymavlink/generator/__init__.py new file mode 100644 index 0000000..2910a8f --- /dev/null +++ b/pymavlink/generator/__init__.py @@ -0,0 +1 @@ +'''pymavlink code generator''' diff --git a/pymavlink/generator/gen_js.sh b/pymavlink/generator/gen_js.sh new file mode 100755 index 0000000..3b444b4 --- /dev/null +++ b/pymavlink/generator/gen_js.sh @@ -0,0 +1,44 @@ +#!/bin/sh + +for protocol in 0.9 1.0; do + for xml in ../../message_definitions/v$protocol/*.xml; do + base=$(basename $xml .xml) + mkdir -p javascript/implementations/mavlink_${base}_v${protocol} + + # Generate MAVLink implementation + ../tools/mavgen.py --lang=JavaScript --wire-protocol=$protocol --output=javascript/implementations/mavlink_${base}_v${protocol}/mavlink.js $xml || exit 1 + + # Create package.json file + cat >javascript/implementations/mavlink_${base}_v${protocol}/package.json <"], + "main" : "mavlink.js", + "repository" : { + "type" : "git", + "url" : "https://github.com/mavlink/mavlink" + }, + "dependencies" : { + "underscore" : "", + "jspack":"", + "winston": "" + }, + "devDependencies" : { + "should" : "", + "mocha" : "", + "sinon" : "" + } +} +EOF + + done +done diff --git a/pymavlink/generator/java/lib/Messages/MAVLinkMessage.java b/pymavlink/generator/java/lib/Messages/MAVLinkMessage.java new file mode 100644 index 0000000..9ed061e --- /dev/null +++ b/pymavlink/generator/java/lib/Messages/MAVLinkMessage.java @@ -0,0 +1,28 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * java mavlink generator tool. It should not be modified by hand. + */ + +package com.MAVLink.Messages; + +import java.io.Serializable; + +import com.MAVLink.MAVLinkPacket; + +public abstract class MAVLinkMessage implements Serializable { + private static final long serialVersionUID = -7754622750478538539L; + // The MAVLink message classes have been changed to implement Serializable, + // this way is possible to pass a mavlink message trought the Service-Acctivity interface + + /** + * Simply a common interface for all MAVLink Messages + */ + + public int sysid; + public int compid; + public int msgid; + public abstract MAVLinkPacket pack(); + public abstract void unpack(MAVLinkPayload payload); +} + \ No newline at end of file diff --git a/pymavlink/generator/java/lib/Messages/MAVLinkPayload.java b/pymavlink/generator/java/lib/Messages/MAVLinkPayload.java new file mode 100644 index 0000000..9a46291 --- /dev/null +++ b/pymavlink/generator/java/lib/Messages/MAVLinkPayload.java @@ -0,0 +1,202 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * java mavlink generator tool. It should not be modified by hand. + */ + +package com.MAVLink.Messages; + +import java.nio.ByteBuffer; + +public class MAVLinkPayload { + + private static final byte UNSIGNED_BYTE_MIN_VALUE = 0; + private static final short UNSIGNED_BYTE_MAX_VALUE = Byte.MAX_VALUE - Byte.MIN_VALUE; + + private static final short UNSIGNED_SHORT_MIN_VALUE = 0; + private static final int UNSIGNED_SHORT_MAX_VALUE = Short.MAX_VALUE - Short.MIN_VALUE; + + private static final int UNSIGNED_INT_MIN_VALUE = 0; + private static final long UNSIGNED_INT_MAX_VALUE = (long) Integer.MAX_VALUE - Integer.MIN_VALUE; + + private static final long UNSIGNED_LONG_MIN_VALUE = 0; + + public static final int MAX_PAYLOAD_SIZE = 255; + + public final ByteBuffer payload; + public int index; + + public MAVLinkPayload(int payloadSize) { + if(payloadSize > MAX_PAYLOAD_SIZE) { + payload = ByteBuffer.allocate(MAX_PAYLOAD_SIZE); + } else { + payload = ByteBuffer.allocate(payloadSize); + } + } + + public ByteBuffer getData() { + return payload; + } + + public int size() { + return payload.position(); + } + + public void add(byte c) { + payload.put(c); + } + + public void resetIndex() { + index = 0; + } + + public byte getByte() { + byte result = 0; + result |= (payload.get(index + 0) & 0xFF); + index += 1; + return result; + } + + public short getUnsignedByte(){ + short result = 0; + result |= payload.get(index + 0) & 0xFF; + index+= 1; + return result; + } + + public short getShort() { + short result = 0; + result |= (payload.get(index + 1) & 0xFF) << 8; + result |= (payload.get(index + 0) & 0xFF); + index += 2; + return result; + } + + public int getUnsignedShort(){ + int result = 0; + result |= (payload.get(index + 1) & 0xFF) << 8; + result |= (payload.get(index + 0) & 0xFF); + index += 2; + return result; + } + + public int getInt() { + int result = 0; + result |= (payload.get(index + 3) & 0xFF) << 24; + result |= (payload.get(index + 2) & 0xFF) << 16; + result |= (payload.get(index + 1) & 0xFF) << 8; + result |= (payload.get(index + 0) & 0xFF); + index += 4; + return result; + } + + public long getUnsignedInt(){ + long result = 0; + result |= (payload.get(index + 3) & 0xFFFFL) << 24; + result |= (payload.get(index + 2) & 0xFFFFL) << 16; + result |= (payload.get(index + 1) & 0xFFFFL) << 8; + result |= (payload.get(index + 0) & 0xFFFFL); + index += 4; + return result; + } + + public long getLong() { + long result = 0; + result |= (payload.get(index + 7) & 0xFFFFL) << 56; + result |= (payload.get(index + 6) & 0xFFFFL) << 48; + result |= (payload.get(index + 5) & 0xFFFFL) << 40; + result |= (payload.get(index + 4) & 0xFFFFL) << 32; + result |= (payload.get(index + 3) & 0xFFFFL) << 24; + result |= (payload.get(index + 2) & 0xFFFFL) << 16; + result |= (payload.get(index + 1) & 0xFFFFL) << 8; + result |= (payload.get(index + 0) & 0xFFFFL); + index += 8; + return result; + } + + public long getUnsignedLong(){ + return getLong(); + } + + public long getLongReverse() { + long result = 0; + result |= (payload.get(index + 0) & 0xFFFFL) << 56; + result |= (payload.get(index + 1) & 0xFFFFL) << 48; + result |= (payload.get(index + 2) & 0xFFFFL) << 40; + result |= (payload.get(index + 3) & 0xFFFFL) << 32; + result |= (payload.get(index + 4) & 0xFFFFL) << 24; + result |= (payload.get(index + 5) & 0xFFFFL) << 16; + result |= (payload.get(index + 6) & 0xFFFFL) << 8; + result |= (payload.get(index + 7) & 0xFFFFL); + index += 8; + return result; + } + + public float getFloat() { + return Float.intBitsToFloat(getInt()); + } + + public void putByte(byte data) { + add(data); + } + + public void putUnsignedByte(short data){ + if(data < UNSIGNED_BYTE_MIN_VALUE || data > UNSIGNED_BYTE_MAX_VALUE){ + throw new IllegalArgumentException("Value is outside of the range of an unsigned byte: " + data); + } + + putByte((byte) data); + } + + public void putShort(short data) { + add((byte) (data >> 0)); + add((byte) (data >> 8)); + } + + public void putUnsignedShort(int data){ + if(data < UNSIGNED_SHORT_MIN_VALUE || data > UNSIGNED_SHORT_MAX_VALUE){ + throw new IllegalArgumentException("Value is outside of the range of an unsigned short: " + data); + } + + putShort((short) data); + } + + public void putInt(int data) { + add((byte) (data >> 0)); + add((byte) (data >> 8)); + add((byte) (data >> 16)); + add((byte) (data >> 24)); + } + + public void putUnsignedInt(long data){ + if(data < UNSIGNED_INT_MIN_VALUE || data > UNSIGNED_INT_MAX_VALUE){ + throw new IllegalArgumentException("Value is outside of the range of an unsigned int: " + data); + } + + putInt((int) data); + } + + public void putLong(long data) { + add((byte) (data >> 0)); + add((byte) (data >> 8)); + add((byte) (data >> 16)); + add((byte) (data >> 24)); + add((byte) (data >> 32)); + add((byte) (data >> 40)); + add((byte) (data >> 48)); + add((byte) (data >> 56)); + } + + public void putUnsignedLong(long data){ + if(data < UNSIGNED_LONG_MIN_VALUE){ + throw new IllegalArgumentException("Value is outside of the range of an unsigned long: " + data); + } + + putLong(data); + } + + public void putFloat(float data) { + putInt(Float.floatToIntBits(data)); + } + +} diff --git a/pymavlink/generator/java/lib/Messages/MAVLinkStats.java b/pymavlink/generator/java/lib/Messages/MAVLinkStats.java new file mode 100644 index 0000000..ac4adf0 --- /dev/null +++ b/pymavlink/generator/java/lib/Messages/MAVLinkStats.java @@ -0,0 +1,77 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * java mavlink generator tool. It should not be modified by hand. + */ + +package com.MAVLink.Messages; + +import com.MAVLink.MAVLinkPacket; + +/** + * Storage for MAVLink Packet and Error statistics + * + */ +public class MAVLinkStats /* implements Serializable */{ + + public int receivedPacketCount; + + public int crcErrorCount; + + public int lostPacketCount; + + private int lastPacketSeq; + + /** + * Check the new received packet to see if has lost someone between this and + * the last packet + * + * @param packet + * Packet that should be checked + */ + public void newPacket(MAVLinkPacket packet) { + advanceLastPacketSequence(); + if (hasLostPackets(packet)) { + updateLostPacketCount(packet); + } + lastPacketSeq = packet.seq; + receivedPacketCount++; + } + + private void updateLostPacketCount(MAVLinkPacket packet) { + int lostPackets; + if (packet.seq - lastPacketSeq < 0) { + lostPackets = (packet.seq - lastPacketSeq) + 255; + } else { + lostPackets = (packet.seq - lastPacketSeq); + } + lostPacketCount += lostPackets; + } + + private boolean hasLostPackets(MAVLinkPacket packet) { + return lastPacketSeq > 0 && packet.seq != lastPacketSeq; + } + + private void advanceLastPacketSequence() { + // wrap from 255 to 0 if necessary + lastPacketSeq = (lastPacketSeq + 1) & 0xFF; + } + + /** + * Called when a CRC error happens on the parser + */ + public void crcError() { + crcErrorCount++; + } + + /** + * Resets statistics for this MAVLink. + */ + public void mavlinkResetStats() { + lastPacketSeq = -1; + lostPacketCount = 0; + crcErrorCount = 0; + receivedPacketCount = 0; + } + +} \ No newline at end of file diff --git a/pymavlink/generator/java/lib/Parser.java b/pymavlink/generator/java/lib/Parser.java new file mode 100644 index 0000000..2ac3b58 --- /dev/null +++ b/pymavlink/generator/java/lib/Parser.java @@ -0,0 +1,132 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * java mavlink generator tool. It should not be modified by hand. + */ + +package com.MAVLink; + +import com.MAVLink.MAVLinkPacket; +import com.MAVLink.Messages.MAVLinkStats; + +public class Parser { + + /** + * States from the parsing state machine + */ + enum MAV_states { + MAVLINK_PARSE_STATE_UNINIT, MAVLINK_PARSE_STATE_IDLE, MAVLINK_PARSE_STATE_GOT_STX, MAVLINK_PARSE_STATE_GOT_LENGTH, MAVLINK_PARSE_STATE_GOT_SEQ, MAVLINK_PARSE_STATE_GOT_SYSID, MAVLINK_PARSE_STATE_GOT_COMPID, MAVLINK_PARSE_STATE_GOT_MSGID, MAVLINK_PARSE_STATE_GOT_CRC1, MAVLINK_PARSE_STATE_GOT_PAYLOAD + } + + MAV_states state = MAV_states.MAVLINK_PARSE_STATE_UNINIT; + + static boolean msg_received; + + public MAVLinkStats stats = new MAVLinkStats(); + private MAVLinkPacket m; + + /** + * This is a convenience function which handles the complete MAVLink + * parsing. the function will parse one byte at a time and return the + * complete packet once it could be successfully decoded. Checksum and other + * failures will be silently ignored. + * + * @param c + * The char to parse + */ + public MAVLinkPacket mavlink_parse_char(int c) { + msg_received = false; + + switch (state) { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + + if (c == MAVLinkPacket.MAVLINK_STX) { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX; + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (msg_received) { + msg_received = false; + state = MAV_states.MAVLINK_PARSE_STATE_IDLE; + } else { + m = new MAVLinkPacket(c); + state = MAV_states.MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + m.seq = c; + state = MAV_states.MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + m.sysid = c; + state = MAV_states.MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + m.compid = c; + state = MAV_states.MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: + m.msgid = c; + if (m.len == 0) { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } else { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + m.payload.add((byte) c); + if (m.payloadIsFilled()) { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: + m.generateCRC(); + // Check first checksum byte + if (c != m.crc.getLSB()) { + msg_received = false; + state = MAV_states.MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLinkPacket.MAVLINK_STX) { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX; + m.crc.start_checksum(); + } + stats.crcError(); + } else { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_CRC1; + } + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + // Check second checksum byte + if (c != m.crc.getMSB()) { + msg_received = false; + state = MAV_states.MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLinkPacket.MAVLINK_STX) { + state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX; + m.crc.start_checksum(); + } + stats.crcError(); + } else { // Successfully received the message + stats.newPacket(m); + msg_received = true; + state = MAV_states.MAVLINK_PARSE_STATE_IDLE; + } + + break; + + } + if (msg_received) { + return m; + } else { + return null; + } + } + +} diff --git a/pymavlink/generator/javascript/Makefile b/pymavlink/generator/javascript/Makefile new file mode 100644 index 0000000..b8fbedf --- /dev/null +++ b/pymavlink/generator/javascript/Makefile @@ -0,0 +1,11 @@ +all: clean + npm install + +test: all + mocha test + +ci: all + mocha --reporter xunit test > mocha.xml + +clean: + rm -rf implementations \ No newline at end of file diff --git a/pymavlink/generator/javascript/README.md b/pymavlink/generator/javascript/README.md new file mode 100644 index 0000000..f41f0e1 --- /dev/null +++ b/pymavlink/generator/javascript/README.md @@ -0,0 +1,141 @@ +## Javascript MAVLink implementation ## + +This code generates ```npm``` modules that can be used with Node.js. As with the other implementations in Python and C, the MAVLink protocol is specified in XML manifests which can be modified to add custom messages. + +*See the gotcha's and todo's section below* for some important caveats. This implementation should be considered pre-beta: it creates a working MAVLink parser, but there's plenty of rough edges in terms of API. + +### Generating the JS implementation ### + +Folders in the ```implementations/``` directory are ```npm``` modules, automatically generated from XML manifests that are in the [mavlink/mavlink](https://github.com/mavlink/mavlink) project. If you wish to generate custom MAVLink packets, you would need to follow the directions there. + +You need to have Node.js and npm installed to build. + +To build the Javascript implementations: + +```bash +npm install +``` + +or + +```bash +make +``` + +(which calls npm) + +### Usage in Node.js ### + +The generated modules emit events when valid MAVLink messages are encountered. The name of the event is the same as the name of the message: ```HEARTBEAT```, ```FETCH_PARAM_LIST```, ```REQUEST_DATA_STREAM```, etc. In addition, a generic ```message``` event is emitted whenever a message is successfully decoded. + +The below code is a rough sketch of how to use the generated module in Node.js. A somewhat more complete (though early, early alpha) example can be found [here](https://github.com/acuasi/ground-control-station). + +#### Generating the parser + +After running the generator, copy the version of the MAVLink protocol you need into your project's ```node_modules``` folder, then enter that directory and install its dependencies using ```npm install```: + +```bash +cp -R javascript/implementations/mavlink_ardupilotmega_v1.0 /path/to/my/project/node_modules/ +cd /path/to/my/project/node_modules/mavlink_ardupilotmega_v1.0 && npm install +``` + +Then, you can use the MAVLink module, as sketched below. + +#### Initializing the parser + +In your ```server.js``` script, you need to include the generated parser and instantiate it; you also need some kind of binary stream library that can read/write binary data and emit an event when new data is ready to be parsed (TCP, UDP, serial port all have appropriate libraries in the npm-o-sphere). The connection's "data is ready" event is bound to invoke the MAVLink parser to try and extract a valid message. + +```javascript +// requires Underscore.js and jspack +// can use Winston for logging +// see package.json for dependencies for the implementation +var mavlink = require('mavlink_ardupilotmega_v1.0'), + net = require('net'); + +// Instantiate the parser +// logger: pass a Winston logger or null if not used +// 1: source system id +// 50: source component id +mavlinkParser = new MAVLink(logger, 1, 50); + +// Create a connection -- can be anything that can receive/send binary +connection = net.createConnection(5760, '127.0.0.1'); + +// When the connection issues a "got data" event, try and parse it +connection.on('data', function(data) { + mavlinkParser.parseBuffer(data); +}); +``` + +#### Receiving MAVLink messages + +If the serial buffer has a valid MAVLink message, the message is removed from the buffer and parsed. Upon parsing a valid message, the MAVLink implementation emits two events: ```message``` (for any message) and the specific message name that was parsed, so you can listen for specific messages and handle them. + +```javascript +// Attach an event handler for any valid MAVLink message +mavlinkParser.on('message', function(message) { + console.log('Got a message of any type!'); + console.log(message); +}); + +// Attach an event handler for a specific MAVLink message +mavlinkParser.on('HEARTBEAT', function(message) { + console.log('Got a heartbeat message!'); + console.log(message); // message is a HEARTBEAT message +}); +``` + +#### Sending MAVLink messages + +*See the gotcha's and todo's section below* for some important caveats. The below code is preliminary and *will* change to be more direct. At this point, the MAVLink parser doesn't manage any state information about the UAV or the connection itself, so a few fields need to be fudged, as indicated below. + +Sending a MAVLink message is done by creating the message object, populating its fields, and packing/sending it across the wire. Messages are defined in the generated code, and you can look up the parameter list/docs for each message type there. For example, the message ```REQUEST_DATA_STREAM``` has this signature: + +```javascript +mavlink.messages.request_data_stream = function(target_system, target_component, req_stream_id, req_message_rate, start_stop) //... +``` + +Creating the message is done like this: + +```javascript +request = new mavlink.messages.request_data_stream(1, 1, mavlink.MAV_DATA_STREAM_ALL, 1, 1); + +// Create a buffer consisting of the packed message, and send it across the wire. +// You need to pass a MAVLink instance to pack. It will then take care of setting sequence number, system and component id. +// Hack alert: the MAVLink connection could/should encapsulate this. +p = new Buffer(request.pack(mavlinkParser)); +connection.write(p); +``` + +### Gotchas and todo's ### + +JavaScript doesn't have 64bit integers (long). The library that replaces Pythons struct converts ```q``` and ```Q``` into 3 part arrays: ```[lowBits, highBits, unsignedFlag]```. These arrays can be used with int64 libraries such as [Long.js](https://github.com/dcodeIO/Long.js). See [int64.js](https://github.com/AndreasAntener/node-jspack/blob/master/test/int64.js) for examples. + +Current implementation tries to be as robust as possible. It doesn't throw errors but emits bad_data messages. Also it discards the buffer of a possible message as soon as if finds a valid prefix. Future improvements: +* Implement not so robust parsing: throw errors (similar to the Python version) +* Implement trying hard: parse buffer char by char and don't just discard the expected length buffer if there is an error + +This code isn't great idiomatic Javascript (yet!), instead, it's more of a line-by-line translation from Python as much as possible. + +The Python MAVLink code manages some information about the connection status (system/component attached, bad packets, durations/times, etc), and that work isn't completely present in this code yet. + +Code to create/send MAVLink messages to a client is very clumsy at this point in time *and will change* to make it more direct. + +Publish generated scripts as npm module. + +### Development ### + +Unit tests cover basic packing/unpacking functionality against mock binary buffers representing valid MAVlink generated by the Python implementation. You need to have [mocha](http://visionmedia.github.com/mocha/) installed to run the unit tests. + +To run tests, use npm: + +```bash +npm test +``` + +Specific instructions for generating Jenkins-friendly output is done through the makefile as well: + +```bash +make ci +``` + diff --git a/pymavlink/generator/javascript/package.json b/pymavlink/generator/javascript/package.json new file mode 100644 index 0000000..f985c20 --- /dev/null +++ b/pymavlink/generator/javascript/package.json @@ -0,0 +1,23 @@ +{ + "name" : "mavlink", + "version" : "0.0.1", + "description" : "Implementation of the MAVLink protocol for various platforms and both 0.9 and 1.0 revisions of MAVLink", + "repository": "private", + "dependencies" : { + "underscore" : "", + "winston": "", + "jspack": "0.0.4" + }, + "devDependencies" : { + "should" : "", + "mocha" : "", + "sinon" : "" + }, + "scripts": { + "preinstall": "rm -rf implementations", + "install": "cd .. && ./gen_js.sh", + + "pretest": "npm install", + "test": "mocha test" + } +} \ No newline at end of file diff --git a/pymavlink/generator/javascript/test/capture.mavlink b/pymavlink/generator/javascript/test/capture.mavlink new file mode 100644 index 0000000..08cd169 Binary files /dev/null and b/pymavlink/generator/javascript/test/capture.mavlink differ diff --git a/pymavlink/generator/javascript/test/mavlink.js b/pymavlink/generator/javascript/test/mavlink.js new file mode 100644 index 0000000..a4e3d37 --- /dev/null +++ b/pymavlink/generator/javascript/test/mavlink.js @@ -0,0 +1,302 @@ +var mavlink = require('../implementations/mavlink_common_v1.0/mavlink.js'), + should = require('should'), + sinon = require('sinon'), + fs = require('fs'); + +// Actual data stream taken from APM. +global.fixtures = global.fixtures || {}; +global.fixtures.serialStream = fs.readFileSync("test/capture.mavlink"); +//global.fixtures.heartbeatBinaryStream = fs.readFileSync("javascript/test/heartbeat-data-fixture"); + +describe("Generated MAVLink protocol handler object", function() { + + beforeEach(function() { + this.m = new MAVLink(); + + // Valid heartbeat payload + this.heartbeatPayload = new Buffer([0xfe, 0x09, 0x03, 0xff , 0x00 , 0x00 , 0x00 , 0x00 , 0x00 , 0x00 , 0x06 , 0x08 , 0x00 , 0x00 , 0x03, 0x9f, 0x5c]); + + // Complete but invalid message + this.completeInvalidMessage = new Buffer([0xfe, 0x00, 0xfe, 0x00, 0x00, 0xe0, 0x00, 0x00]); + }); + + describe("message header handling", function() { + + it("IDs and sequence numbers are set on send", function(){ + var mav = new MAVLink(null, 42, 99); + var writer = { + write: function(){} + }; + mav.file = writer; + var spy = sinon.spy(writer, 'write'); + + var msg = new mavlink.messages['heartbeat'](); + mav.send(msg); + + spy.calledOnce.should.be.true; + spy.getCall(0).args[0][2].should.be.eql(0); // seq + spy.getCall(0).args[0][3].should.be.eql(42); // sys + spy.getCall(0).args[0][4].should.be.eql(99); // comp + }); + + it("sequence number increases on send", function(){ + var mav = new MAVLink(null, 42, 99); + var writer = { + write: function(){} + }; + mav.file = writer; + var spy = sinon.spy(writer, 'write'); + + var msg = new mavlink.messages['heartbeat'](); + mav.send(msg); + mav.send(msg); + + spy.callCount.should.be.eql(2); + spy.getCall(0).args[0][2].should.be.eql(0); // seq + spy.getCall(0).args[0][3].should.be.eql(42); // sys + spy.getCall(0).args[0][4].should.be.eql(99); // comp + spy.getCall(1).args[0][2].should.be.eql(1); // seq + spy.getCall(1).args[0][3].should.be.eql(42); // sys + spy.getCall(1).args[0][4].should.be.eql(99); // comp + }); + + it("sequence number turns over at 256", function(){ + var mav = new MAVLink(null, 42, 99); + var writer = { + write: function(){} + }; + mav.file = writer; + var spy = sinon.spy(writer, 'write'); + + var msg = new mavlink.messages['heartbeat'](); + + for(var i = 0; i < 258; i++){ + mav.send(msg); + var seq = i % 256; + spy.getCall(i).args[0][2].should.be.eql(seq); // seq + } + }); + + }); + + describe("buffer decoder (parseBuffer)", function() { + + // This test prepopulates a single message as a binary buffer. + it("decodes a binary stream representation of a single message correctly", function() { + this.m.pushBuffer(global.fixtures.heartbeatBinaryStream); + var messages = this.m.parseBuffer(); + + }); + + // This test includes a "noisy" signal, with non-mavlink data/messages/noise. + it("decodes a real serial binary stream into an array of MAVLink messages", function() { + this.m.pushBuffer(global.fixtures.serialStream); + var messages = this.m.parseBuffer(); + }); + + it("decodes at most one message, even if there are more in its buffer", function() { + + }); + + it("returns null while no packet is available", function() { + (this.m.parseBuffer() === null).should.equal(true); // should's a bit tortured here + }); + + }); + + describe("decoding chain (parseChar)", function() { + + it("returns a bad_data message if a borked message is encountered", function() { + var b = new Buffer([3, 0, 1, 2, 3, 4, 5]); // invalid message + var message = this.m.parseChar(b); + message.should.be.an.instanceof(mavlink.messages.bad_data); + }); + + it("emits a 'message' event, provisioning callbacks with the message", function(done) { + this.m.on('message', function(message) { + message.should.be.an.instanceof(mavlink.messages.heartbeat); + done(); + }); + this.m.parseChar(this.heartbeatPayload); + }); + + it("emits a 'message' event for bad messages, provisioning callbacks with the message", function(done) { + var b = new Buffer([3, 0, 1, 2, 3, 4, 5]); // invalid message + this.m.on('message', function(message) { + message.should.be.an.instanceof(mavlink.messages.bad_data); + done(); + }); + this.m.parseChar(b); + }); + + it("on bad prefix: cuts-off first char in buffer and returns correct bad data", function() { + var b = new Buffer([3, 0, 1, 2, 3, 4, 5]); // invalid message + var message = this.m.parseChar(b); + message.msgbuf.length.should.be.eql(1); + message.msgbuf[0].should.be.eql(3); + this.m.buf.length.should.be.eql(6); + // should process next char + message = this.m.parseChar(); + message.msgbuf.length.should.be.eql(1); + message.msgbuf[0].should.be.eql(0); + this.m.buf.length.should.be.eql(5); + }); + + it("on bad message: cuts-off message length and returns correct bad data", function() { + var message = this.m.parseChar(this.completeInvalidMessage); + message.msgbuf.length.should.be.eql(8); + message.msgbuf.should.be.eql(this.completeInvalidMessage); + this.m.buf.length.should.be.eql(0); + }); + + it("error counter is raised on error", function() { + var message = this.m.parseChar(this.completeInvalidMessage); + this.m.total_receive_errors.should.equal(1); + var message = this.m.parseChar(this.completeInvalidMessage); + this.m.total_receive_errors.should.equal(2); + }); + + // TODO: there is a option in python: robust_parsing. Maybe we should port this as well. + // If robust_parsing is off, the following should be tested: + // - (maybe) not returning subsequent errors for prefix errors + // - errors are thrown instead of catched inside + + // TODO: add tests for "try hard" parsing when implemented + + }); + + describe("stream buffer accumulator", function() { + + it("increments total bytes received", function() { + this.m.total_bytes_received.should.equal(0); + var b = new Buffer(16); + b.fill("h"); + this.m.pushBuffer(b); + this.m.total_bytes_received.should.equal(16); + }); + + it("appends data to its local buffer", function() { + this.m.buf.length.should.equal(0); + var b = new Buffer(16); + b.fill("h"); + this.m.pushBuffer(b); + this.m.buf.should.eql(b); // eql = wiggly equality + }); + }); + + describe("prefix decoder", function() { + + it("consumes, unretrievably, the first byte of the buffer, if its a bad prefix", function() { + + var b = new Buffer([1, 254]); + this.m.pushBuffer(b); + + // eat the exception here. + try { + this.m.parsePrefix(); + } catch (e) { + this.m.buf.length.should.equal(1); + this.m.buf[0].should.equal(254); + } + + }); + + it("throws an exception if a malformed prefix is encountered", function() { + + var b = new Buffer([15, 254, 1, 7, 7]); // borked system status packet, invalid + this.m.pushBuffer(b); + var m = this.m; + (function() { m.parsePrefix(); }).should.throw('Bad prefix (15)'); + + }); + + }); + + describe("length decoder", function() { + it("updates the expected length to the size of the expected full message", function() { + this.m.expected_length.should.equal(6); // default, header size + var b = new Buffer([254, 1, 1]); // packet length = 1 + this.m.pushBuffer(b); + this.m.parseLength(); + this.m.expected_length.should.equal(9); // 1+8 bytes for the message header + }); + }); + + describe("payload decoder", function() { + + it("resets the expected length of the next packet to 6 (header)", function() { + this.m.pushBuffer(this.heartbeatPayload); + this.m.parseLength(); // expected length should now be 9 (message) + 8 bytes (header) = 17 + this.m.expected_length.should.equal(17); + this.m.parsePayload(); + this.m.expected_length.should.equal(6); + }); + + it("submits a candidate message to the mavlink decode function", function() { + + var spy = sinon.spy(this.m, 'decode'); + + this.m.pushBuffer(this.heartbeatPayload); + this.m.parseLength(); + this.m.parsePayload(); + + // could improve this to check the args more closely. + // It'd be better but tricky because the type comparison doesn't quite work. + spy.called.should.be.true; + + }); + + // invalid data should return bad_data message + it("parsePayload throws exception if a borked message is encountered", function() { + var b = new Buffer([3, 0, 1, 2, 3, 4, 5]); // invalid message + this.m.pushBuffer(b); + var message; + (function(){ + message = this.m.parsePayload(); + }).should.throw(); + }); + + it("returns a valid mavlink packet if everything is OK", function() { + this.m.pushBuffer(this.heartbeatPayload); + this.m.parseLength(); + var message = this.m.parsePayload(); + message.should.be.an.instanceof(mavlink.messages.heartbeat); + }); + + it("increments the total packets received if a good packet is decoded", function() { + this.m.total_packets_received.should.equal(0); + this.m.pushBuffer(this.heartbeatPayload); + this.m.parseLength(); + var message = this.m.parsePayload(); + this.m.total_packets_received.should.equal(1); + }); + + + + }); + +}); + + +describe("MAVLink X25CRC Decoder", function() { + + beforeEach(function() { + // Message header + payload, lacks initial MAVLink flag (FE) and CRC. + this.heartbeatMessage = new Buffer([0x09, 0x03, 0xff , 0x00 , 0x00 , 0x00 , 0x00 , 0x00 , 0x00 , 0x06 , 0x08 , 0x00 , 0x00 , 0x03]); + + }); + + // This test matches the output directly taken by inspecting what the Python implementation + // generated for the above packet. + it('implements x25crc function', function() { + mavlink.x25Crc(this.heartbeatMessage).should.equal(27276); + }); + + // Heartbeat crc_extra value is 50. + it('can accumulate further bytes as needed (crc_extra)', function() { + var crc = mavlink.x25Crc(this.heartbeatMessage); + crc = mavlink.x25Crc([50], crc); + crc.should.eql(23711) + }); + +}); \ No newline at end of file diff --git a/pymavlink/generator/javascript/test/message.js b/pymavlink/generator/javascript/test/message.js new file mode 100644 index 0000000..fae68c1 --- /dev/null +++ b/pymavlink/generator/javascript/test/message.js @@ -0,0 +1,252 @@ +var mavlink = require('../implementations/mavlink_common_v1.0/mavlink.js'), + should = require('should'); + +describe('MAVLink message registry', function() { + + it('defines constructors for every message', function() { + mavlink.messages['gps_raw_int'].should.be.a.function; + }); + + it('assigns message properties, format with int64 (q), gps_raw_int', function() { + var m = new mavlink.messages['gps_raw_int'](); + m.format.should.equal(" garbage collection! + """ + self.getRootNode().unlink() + + + def __str__ (self): + """Return the string representation of the contained XML tree.""" + return self.printTree() + + + +######################################## +# Element wrapper API (interface class) +# + +class XmlElementWrapper: + """XML element wrapper API. + + Contains a XML element node + All not implemented methods have to be overloaded by the derived class!! + """ + + def __init__(self, element, treeWrapper, curNs=[], initAttrSeq=1): + """Constructor of wrapper class XmlElementWrapper. + + Input parameter: + element: XML element node which is wrapped by this object + treeWrapper: XML tree wrapper class the current element belongs to + curNs: namespaces for scope of this element + """ + self.element = element + self.element.xmlIfExtElementWrapper = self + self.treeWrapper = treeWrapper + self.nodeUsedByExternalCache = 0 + + if self.__useCaching(): + self.__childrenCache = {} + self.__firstChildCache = {} + self.__qNameAttrCache = {} + + self.baseUrl = None + self.absUrl = None + self.filePath = None + self.startLineNumber = None + self.endLineNumber = None + self.curNs = curNs[:] + self.attributeSequence = [] + + if initAttrSeq: + self.attributeSequence = self.getAttributeDict().keys() + + + def unlink (self): + """Break circular references of this element and its children.""" + for childWrapper in self.getChildren(): + childWrapper.unlink() + if not self.isUsedByExternalCache(): + self.element.xmlIfExtUnlink() + + + def cloneNode (self, deep, cloneCallback=None): + """Create a copy of the current element wrapper. + The reference to the parent node is set to None!""" + elementCopy = self.element.xmlIfExtCloneNode() + elementWrapperCopy = self.__class__(elementCopy, self.treeWrapper, initAttrSeq=0) + elementWrapperCopy.treeWrapper = None + elementWrapperCopy.baseUrl = self.baseUrl + elementWrapperCopy.absUrl = self.absUrl + elementWrapperCopy.filePath = self.filePath + elementWrapperCopy.startLineNumber = self.startLineNumber + elementWrapperCopy.endLineNumber = self.endLineNumber + elementWrapperCopy.curNs = self.curNs[:] + elementWrapperCopy.attributeSequence = self.attributeSequence[:] + if cloneCallback: cloneCallback(elementWrapperCopy) + if deep: + for childElement in self.element.xmlIfExtGetChildren(): + childWrapperElementCopy = childElement.xmlIfExtElementWrapper.cloneNode(deep, cloneCallback) + childWrapperElementCopy.element.xmlIfExtSetParentNode(elementWrapperCopy.element) + elementWrapperCopy.element.xmlIfExtAppendChild(childWrapperElementCopy.element) + return elementWrapperCopy + + + def clearNodeCache (self): + """Clear all caches used by this element wrapper which contains element wrapper references.""" + self.__clearChildrenCache() + + + def isUsedByExternalCache (self): + """Check if this node is used by an external cache. + unlink commands are ignored if used by an external cache""" + return self.nodeUsedByExternalCache + + + def setExternalCacheUsage (self, used, deep=1): + """Set external cache usage for this node and its children + unlink commands are ignored if used by an external cache + + Input parameter: + used: 0 or 1 (used by external cache) + deep: 0 or 1: controls if the child elements are also marked as used by external cache + """ + self.nodeUsedByExternalCache = used + if deep: + for childWrapper in self.getChildren(): + childWrapper.setExternalCacheUsage (used, deep) + + + + ########################################################## + # attributes of the current node can be accessed via key operator + + def __getitem__(self, tupleOrAttrName): + """Attributes of the contained element node can be accessed via key operator. + + Input parameter: + tupleOrAttrName: name of the attribute (tuple of namespace and attributeName or only attributeName) + Returns the attribute value. + """ + attrValue = self.getAttribute (tupleOrAttrName) + if attrValue != None: + return attrValue + else: + raise AttributeError, "Attribute %s not found!" %(repr(tupleOrAttrName)) + + + def __setitem__(self, tupleOrAttrName, attributeValue): + """Attributes of the contained element node can be accessed via key operator. + + Input parameter: + tupleOrAttrName: name of the attribute (tuple of namespace and attributeName or only attributeName) + attributeValue: attribute value to be set + """ + self.setAttribute (tupleOrAttrName, attributeValue) + + +#++++++++++++ methods concerning the tag name ++++++++++++++++++++++++ + + def getTagName (self): + """Retrieve the (complete) tag name of the contained element node + + Returns the (complete) tag name of the contained element node + """ + return self.element.xmlIfExtGetTagName() + + + def getLocalName (self): + """Retrieve the local name (without namespace) of the contained element node + + Returns the local name (without namespace) of the contained element node + """ + + try: + return self.__localNameCache + except: + prefix, localName = splitQName (self.getTagName()) + if self.__useCaching(): + self.__localNameCache = localName + return localName + + + def getNamespaceURI (self): + """Retrieve the namespace URI of the contained element node + + Returns the namespace URI of the contained element node (None if no namespace is used). + """ + try: + return self.__nsUriCache + except: + prefix = self.element.xmlIfExtGetNamespaceURI() + if self.__useCaching(): + self.__nsUriCache = prefix + return prefix + + + def getNsName (self): + """Retrieve a tuple (namespace, localName) of the contained element node + + Returns a tuple (namespace, localName) of the contained element node (namespace is None if no namespace is used). + """ + try: + return self.__nsNameCache + except: + nsName = NsNameTupleFactory( (self.getNamespaceURI(), self.getLocalName()) ) + if self.__useCaching(): + self.__nsNameCache = nsName + return nsName + + + def getQName (self): + """Retrieve a string prefix and localName of the contained element node + + Returns a string "prefix:localName" of the contained element node + """ + return self.nsName2QName(self.getNsName()) + + + def getPrefix (self): + """Retrieve the namespace prefix of the contained element node + + Returns the namespace prefix of the contained element node (None if no namespace is used). + """ + return self.getNsPrefix(self.getNsName()) + + +#++++++++++++ methods concerning print support ++++++++++++++++++++++++ + + def __str__ (self): + """Retrieve the textual representation of the contained element node.""" + return self.printNode() + + + def printNode (self, indent="", deep=0, prettyPrint=0, attrMaxLengthDict={}, printElementValue=1, encoding=None): + """Retrieve the textual representation of the contained element node. + + Input parameter: + indent: indentation to be used for string representation + deep: 0 or 1: controls if the child element nodes are also printed + prettyPrint: aligns the columns of the attributes of childNodes + attrMaxLengthDict: dictionary containing the length of the attribute values (used for prettyprint) + printElementValue: 0 or 1: controls if the element value is printed + Returns the string representation + """ + patternXmlTagShort = '''\ +%(indent)s<%(qName)s%(attributeString)s/>%(tailText)s%(lf)s''' + + patternXmlTagLong = '''\ +%(indent)s<%(qName)s%(attributeString)s>%(elementValueString)s\ +%(lf)s%(subTreeString)s\ +%(indent)s%(tailText)s%(lf)s''' + + subTreeStringList = [] + tailText = "" + addIndent = "" + lf = "" + if deep: + childAttrMaxLengthDict = {} + if prettyPrint: + for childNode in self.getChildren(): + childNode.__updateAttrMaxLengthDict(childAttrMaxLengthDict) + lf = "\n" + addIndent = " " + for childNode in self.getChildren(): + subTreeStringList.append (childNode.printNode(indent + addIndent, deep, prettyPrint, childAttrMaxLengthDict, printElementValue)) + tailText = escapeCdata(self.element.xmlIfExtGetElementTailText(), encoding) + + attributeStringList = [] + for attrName in self.getAttributeList(): + attrValue = escapeAttribute(self.getAttribute(attrName), encoding) + if prettyPrint: + try: + align = attrMaxLengthDict[attrName] + except: + align = len(attrValue) + else: + align = len(attrValue) + qName = self.nsName2QName(attrName) + attributeStringList.append (' %s="%s"%*s' %(qName, attrValue, align - len(attrValue), "")) + attributeString = string.join (attributeStringList, "") + + qName = self.getQName() + if printElementValue: + if deep: + elementValueString = escapeCdata(self.element.xmlIfExtGetElementText(), encoding) + else: + elementValueString = escapeCdata(self.getElementValue(ignoreEmtpyStringFragments=1), encoding) + else: + elementValueString = "" + + if subTreeStringList == [] and elementValueString == "": + printPattern = patternXmlTagShort + else: + if subTreeStringList != []: + subTreeString = string.join (subTreeStringList, "") + else: + subTreeString = "" + printPattern = patternXmlTagLong + return printPattern % vars() + + +#++++++++++++ methods concerning the parent of the current node ++++++++++++++++++++++++ + + def getParentNode (self): + """Retrieve the ElementWrapper object of the parent element node. + + Returns the ElementWrapper object of the parent element node. + """ + parent = self.element.xmlIfExtGetParentNode() + if parent != None: + return parent.xmlIfExtElementWrapper + else: + return None + + +#++++++++++++ methods concerning the children of the current node ++++++++++++++++++++++++ + + + def getChildren (self, tagFilter=None): + """Retrieve the ElementWrapper objects of the children element nodes. + + Input parameter: + tagFilter: retrieve only the children with this tag name ('*' or None returns all children) + Returns all children of this element node which match 'tagFilter' (list) + """ + if tagFilter in (None, '*', (None, '*')): + children = self.element.xmlIfExtGetChildren() + elif tagFilter[1] == '*': + # handle (namespace, '*') + children = filter(lambda child:child.xmlIfExtElementWrapper.getNamespaceURI() == tagFilter[0], + self.element.xmlIfExtGetChildren()) + else: + nsNameFilter = NsNameTupleFactory(tagFilter) + try: + children = self.__childrenCache[nsNameFilter] + except: + children = self.element.xmlIfExtGetChildren(nsNameFilter) + if self.__useCaching(): + self.__childrenCache[nsNameFilter] = children + + return map(lambda child: child.xmlIfExtElementWrapper, children) + + + def getChildrenNS (self, namespaceURI, tagFilter=None): + """Retrieve the ElementWrapper objects of the children element nodes using a namespace. + + Input parameter: + namespaceURI: the namespace URI of the children or None + tagFilter: retrieve only the children with this localName ('*' or None returns all children) + Returns all children of this element node which match 'namespaceURI' and 'tagFilter' (list) + """ + return self.getChildren((namespaceURI, tagFilter)) + + + def getChildrenWithKey (self, tagFilter=None, keyAttr=None, keyValue=None): + """Retrieve the ElementWrapper objects of the children element nodes. + + Input parameter: + tagFilter: retrieve only the children with this tag name ('*' or None returns all children) + keyAttr: name of the key attribute + keyValue: value of the key + Returns all children of this element node which match 'tagFilter' (list) + """ + children = self.getChildren(tagFilter) + return filter(lambda child:child[keyAttr]==keyValue, children) + + + def getFirstChild (self, tagFilter=None): + """Retrieve the ElementWrapper objects of the first child element node. + + Input parameter: + tagFilter: retrieve only the first child with this tag name ('*' or None: no filter) + Returns the first child of this element node which match 'tagFilter' + or None if no suitable child element was found + """ + if tagFilter in (None, '*', (None, '*')): + element = self.element.xmlIfExtGetFirstChild() + elif tagFilter[1] == '*': + # handle (namespace, '*') + children = filter(lambda child:child.xmlIfExtElementWrapper.getNamespaceURI() == tagFilter[0], + self.element.xmlIfExtGetChildren()) + try: + element = children[0] + except: + element = None + else: + nsNameFilter = NsNameTupleFactory(tagFilter) + try: + element = self.__firstChildCache[nsNameFilter] + except: + element = self.element.xmlIfExtGetFirstChild(nsNameFilter) + if self.__useCaching(): + self.__firstChildCache[nsNameFilter] = element + + if element != None: + return element.xmlIfExtElementWrapper + else: + return None + + + def getFirstChildNS (self, namespaceURI, tagFilter=None): + """Retrieve the ElementWrapper objects of the first child element node using a namespace. + + Input parameter: + namespaceURI: the namespace URI of the children or None + tagFilter: retrieve only the first child with this localName ('*' or None: no filter) + Returns the first child of this element node which match 'namespaceURI' and 'tagFilter' + or None if no suitable child element was found + """ + return self.getFirstChild ((namespaceURI, tagFilter)) + + + def getFirstChildWithKey (self, tagFilter=None, keyAttr=None, keyValue=None): + """Retrieve the ElementWrapper objects of the children element nodes. + + Input parameter: + tagFilter: retrieve only the children with this tag name ('*' or None returns all children) + keyAttr: name of the key attribute + keyValue: value of the key + Returns all children of this element node which match 'tagFilter' (list) + """ + children = self.getChildren(tagFilter) + childrenWithKey = filter(lambda child:child[keyAttr]==keyValue, children) + if childrenWithKey != []: + return childrenWithKey[0] + else: + return None + + + def getElementsByTagName (self, tagFilter=None): + """Retrieve all descendant ElementWrapper object of current node whose tag name match 'tagFilter'. + + Input parameter: + tagFilter: retrieve only the children with this tag name ('*' or None returns all descendants) + Returns all descendants of this element node which match 'tagFilter' (list) + """ + if tagFilter in (None, '*', (None, '*'), (None, None)): + descendants = self.element.xmlIfExtGetElementsByTagName() + + elif tagFilter[1] == '*': + # handle (namespace, '*') + descendants = filter(lambda desc:desc.xmlIfExtElementWrapper.getNamespaceURI() == tagFilter[0], + self.element.xmlIfExtGetElementsByTagName()) + else: + nsNameFilter = NsNameTupleFactory(tagFilter) + descendants = self.element.xmlIfExtGetElementsByTagName(nsNameFilter) + + return map(lambda descendant: descendant.xmlIfExtElementWrapper, descendants) + + + def getElementsByTagNameNS (self, namespaceURI, tagFilter=None): + """Retrieve all descendant ElementWrapper object of current node whose tag name match 'namespaceURI' and 'tagFilter'. + + Input parameter: + namespaceURI: the namespace URI of the descendants or None + tagFilter: retrieve only the descendants with this localName ('*' or None returns all descendants) + Returns all descendants of this element node which match 'namespaceURI' and 'tagFilter' (list) + """ + return self.getElementsByTagName((namespaceURI, tagFilter)) + + + def getIterator (self, tagFilter=None): + """Creates a tree iterator. The iterator loops over this element + and all subelements, in document order, and returns all elements + whose tag name match 'tagFilter'. + + Input parameter: + tagFilter: retrieve only the children with this tag name ('*' or None returns all descendants) + Returns all element nodes which match 'tagFilter' (list) + """ + if tagFilter in (None, '*', (None, '*'), (None, None)): + matchingElements = self.element.xmlIfExtGetIterator() + elif tagFilter[1] == '*': + # handle (namespace, '*') + matchingElements = filter(lambda desc:desc.xmlIfExtElementWrapper.getNamespaceURI() == tagFilter[0], + self.element.xmlIfExtGetIterator()) + else: + nsNameFilter = NsNameTupleFactory(tagFilter) + matchingElements = self.element.xmlIfExtGetIterator(nsNameFilter) + + return map(lambda e: e.xmlIfExtElementWrapper, matchingElements) + + + def appendChild (self, tupleOrLocalNameOrElement, attributeDict={}): + """Append an element node to the children of the current node. + + Input parameter: + tupleOrLocalNameOrElement: (namespace, localName) or tagName or ElementWrapper object of the new child + attributeDict: attribute dictionary containing the attributes of the new child (optional) + If not an ElementWrapper object is given, a new ElementWrapper object is created with tupleOrLocalName + Returns the ElementWrapper object of the new child. + """ + if not isinstance(tupleOrLocalNameOrElement, self.__class__): + childElementWrapper = self.__createElement (tupleOrLocalNameOrElement, attributeDict) + else: + childElementWrapper = tupleOrLocalNameOrElement + self.element.xmlIfExtAppendChild (childElementWrapper.element) + self.__clearChildrenCache(childElementWrapper.getNsName()) + return childElementWrapper + + + def insertBefore (self, tupleOrLocalNameOrElement, refChild, attributeDict={}): + """Insert an child element node before the given reference child of the current node. + + Input parameter: + tupleOrLocalNameOrElement: (namespace, localName) or tagName or ElementWrapper object of the new child + refChild: reference child ElementWrapper object + attributeDict: attribute dictionary containing the attributes of the new child (optional) + If not an ElementWrapper object is given, a new ElementWrapper object is created with tupleOrLocalName + Returns the ElementWrapper object of the new child. + """ + if not isinstance(tupleOrLocalNameOrElement, self.__class__): + childElementWrapper = self.__createElement (tupleOrLocalNameOrElement, attributeDict) + else: + childElementWrapper = tupleOrLocalNameOrElement + if refChild == None: + self.appendChild (childElementWrapper) + else: + self.element.xmlIfExtInsertBefore(childElementWrapper.element, refChild.element) + self.__clearChildrenCache(childElementWrapper.getNsName()) + return childElementWrapper + + + def removeChild (self, childElementWrapper): + """Remove the given child element node from the children of the current node. + + Input parameter: + childElementWrapper: ElementWrapper object to be removed + """ + self.element.xmlIfExtRemoveChild(childElementWrapper.element) + self.__clearChildrenCache(childElementWrapper.getNsName()) + + + def insertSubtree (self, refChildWrapper, subTreeWrapper, insertSubTreeRootNode=1): + """Insert the given subtree before 'refChildWrapper' ('refChildWrapper' is not removed!) + + Input parameter: + refChildWrapper: reference child ElementWrapper object + subTreeWrapper: subtree wrapper object which contains the subtree to be inserted + insertSubTreeRootNode: if 1, root node of subtree is inserted into parent tree, otherwise not + """ + if refChildWrapper != None: + self.element.xmlIfExtInsertSubtree (refChildWrapper.element, subTreeWrapper.getTree(), insertSubTreeRootNode) + else: + self.element.xmlIfExtInsertSubtree (None, subTreeWrapper.getTree(), insertSubTreeRootNode) + self.__clearChildrenCache() + + + + def replaceChildBySubtree (self, childElementWrapper, subTreeWrapper, insertSubTreeRootNode=1): + """Replace child element node by XML subtree (e.g. expanding included XML files) + + Input parameter: + childElementWrapper: ElementWrapper object to be replaced + subTreeWrapper: XML subtree wrapper object to be inserted + insertSubTreeRootNode: if 1, root node of subtree is inserted into parent tree, otherwise not + """ + self.insertSubtree (childElementWrapper, subTreeWrapper, insertSubTreeRootNode) + self.removeChild(childElementWrapper) + + +#++++++++++++ methods concerning the attributes of the current node ++++++++++++++++++++++++ + + def getAttributeDict (self): + """Retrieve a dictionary containing all attributes of the current element node. + + Returns a dictionary (copy) containing all attributes of the current element node. + """ + return self.element.xmlIfExtGetAttributeDict() + + + def getAttributeList (self): + """Retrieve a list containing all attributes of the current element node + in the sequence specified in the input XML file. + + Returns a list (copy) containing all attributes of the current element node + in the sequence specified in the input XML file (TODO: does currently not work for 4DOM/pyXML interface). + """ + attrList = map(lambda a: NsNameTupleFactory(a), self.attributeSequence) + return attrList + + + def getAttribute (self, tupleOrAttrName): + """Retrieve an attribute value of the current element node. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + Returns the value of the specified attribute. + """ + nsName = NsNameTupleFactory(tupleOrAttrName) + return self.element.xmlIfExtGetAttribute(nsName) + + + def getAttributeOrDefault (self, tupleOrAttrName, defaultValue): + """Retrieve an attribute value of the current element node or the given default value if the attribute doesn't exist. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + Returns the value of the specified attribute or the given default value if the attribute doesn't exist. + """ + attributeValue = self.getAttribute (tupleOrAttrName) + if attributeValue == None: + attributeValue = defaultValue + return attributeValue + + + def getQNameAttribute (self, tupleOrAttrName): + """Retrieve a QName attribute value of the current element node. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + Returns the value of the specified QName attribute as tuple (namespace, localName), + i.e. the prefix is converted into the corresponding namespace value. + """ + nsNameAttrName = NsNameTupleFactory(tupleOrAttrName) + try: + return self.__qNameAttrCache[nsNameAttrName] + except: + qNameValue = self.getAttribute (nsNameAttrName) + nsNameValue = self.qName2NsName(qNameValue, useDefaultNs=1) + if self.__useCaching(): + self.__qNameAttrCache[nsNameAttrName] = nsNameValue + return nsNameValue + + + def hasAttribute (self, tupleOrAttrName): + """Checks if the requested attribute exist for the current element node. + + Returns 1 if the attribute exists, otherwise 0. + """ + nsName = NsNameTupleFactory(tupleOrAttrName) + attrValue = self.element.xmlIfExtGetAttribute(nsName) + if attrValue != None: + return 1 + else: + return 0 + + + def setAttribute (self, tupleOrAttrName, attributeValue): + """Sets an attribute value of the current element node. + If the attribute does not yet exist, it will be created. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + attributeValue: attribute value to be set + """ + if not isinstance(attributeValue, StringTypes): + raise TypeError, "%s (attribute %s) must be a string!" %(repr(attributeValue), repr(tupleOrAttrName)) + + nsNameAttrName = NsNameTupleFactory(tupleOrAttrName) + if nsNameAttrName not in self.attributeSequence: + self.attributeSequence.append(nsNameAttrName) + + if self.__useCaching(): + if self.__qNameAttrCache.has_key(nsNameAttrName): + del self.__qNameAttrCache[nsNameAttrName] + + self.element.xmlIfExtSetAttribute(nsNameAttrName, attributeValue, self.getCurrentNamespaces()) + + + def setAttributeDefault (self, tupleOrAttrName, defaultValue): + """Create attribute and set value to default if it does not yet exist for the current element node. + If the attribute is already existing nothing is done. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + defaultValue: default attribute value to be set + """ + if not self.hasAttribute(tupleOrAttrName): + self.setAttribute(tupleOrAttrName, defaultValue) + + + def removeAttribute (self, tupleOrAttrName): + """Removes an attribute from the current element node. + No exception is raised if there is no matching attribute. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + """ + nsNameAttrName = NsNameTupleFactory(tupleOrAttrName) + + if self.__useCaching(): + if self.__qNameAttrCache.has_key(nsNameAttrName): + del self.__qNameAttrCache[nsNameAttrName] + + self.element.xmlIfExtRemoveAttribute(nsNameAttrName) + + + def processWsAttribute (self, tupleOrAttrName, wsAction): + """Process white space action for the specified attribute according to requested 'wsAction'. + + Input parameter: + tupleOrAttrName: tuple '(namespace, attributeName)' or 'attributeName' if no namespace is used + wsAction: 'collapse': substitute multiple whitespace characters by a single ' ' + 'replace': substitute each whitespace characters by a single ' ' + """ + attributeValue = self.getAttribute(tupleOrAttrName) + newValue = processWhitespaceAction (attributeValue, wsAction) + if newValue != attributeValue: + self.setAttribute(tupleOrAttrName, newValue) + return newValue + + +#++++++++++++ methods concerning the content of the current node ++++++++++++++++++++++++ + + def getElementValue (self, ignoreEmtpyStringFragments=0): + """Retrieve the content of the current element node. + + Returns the content of the current element node as string. + The content of multiple text nodes / CDATA nodes are concatenated to one string. + + Input parameter: + ignoreEmtpyStringFragments: if 1, text nodes containing only whitespaces are ignored + """ + return "".join (self.getElementValueFragments(ignoreEmtpyStringFragments)) + + + def getElementValueFragments (self, ignoreEmtpyStringFragments=0): + """Retrieve the content of the current element node as value fragment list. + + Returns the content of the current element node as list of string fragments. + Each list element represents one text nodes / CDATA node. + + Input parameter: + ignoreEmtpyStringFragments: if 1, text nodes containing only whitespaces are ignored + + Method has to be implemented by derived classes! + """ + return self.element.xmlIfExtGetElementValueFragments (ignoreEmtpyStringFragments) + + + def setElementValue (self, elementValue): + """Set the content of the current element node. + + Input parameter: + elementValue: string containing the new element value + If multiple text nodes / CDATA nodes are existing, 'elementValue' is set + for the first text node / CDATA node. All other text nodes /CDATA nodes are set to ''. + """ + self.element.xmlIfExtSetElementValue(elementValue) + + + def processWsElementValue (self, wsAction): + """Process white space action for the content of the current element node according to requested 'wsAction'. + + Input parameter: + wsAction: 'collapse': substitute multiple whitespace characters by a single ' ' + 'replace': substitute each whitespace characters by a single ' ' + """ + self.element.xmlIfExtProcessWsElementValue(wsAction) + return self.getElementValue() + + +#++++++++++++ methods concerning the info about the current node in the XML file ++++++++++++++++++++ + + + def getStartLineNumber (self): + """Retrieve the start line number of the current element node. + + Returns the start line number of the current element node in the XML file + """ + return self.startLineNumber + + + def getEndLineNumber (self): + """Retrieve the end line number of the current element node. + + Returns the end line number of the current element node in the XML file + """ + return self.endLineNumber + + + def getAbsUrl (self): + """Retrieve the absolute URL of the XML file the current element node belongs to. + + Returns the absolute URL of the XML file the current element node belongs to. + """ + return self.absUrl + + + def getBaseUrl (self): + """Retrieve the base URL of the XML file the current element node belongs to. + + Returns the base URL of the XML file the current element node belongs to. + """ + return self.baseUrl + + + def getFilePath (self): + """Retrieve the file path of the XML file the current element node belongs to. + + Returns the file path of the XML file the current element node belongs to. + """ + return self.filePath + + + def getLocation (self, end=0, fullpath=0): + """Retrieve a string containing file name and line number of the current element node. + + Input parameter: + end: 1 if end line number shall be shown, 0 for start line number + fullpath: 1 if the full path of the XML file shall be shown, 0 for only the file name + Returns a string containing file name and line number of the current element node. + (e.g. to be used for traces or error messages) + """ + lineMethod = (self.getStartLineNumber, self.getEndLineNumber) + pathFunc = (os.path.basename, os.path.abspath) + return "%s, %d" % (pathFunc[fullpath](self.getFilePath()), lineMethod[end]()) + + +#++++++++++++ miscellaneous methods concerning namespaces ++++++++++++++++++++ + + + def getCurrentNamespaces (self): + """Retrieve the namespace prefixes visible for the current element node + + Returns a list of the namespace prefixes visible for the current node. + """ + return self.curNs + + + def qName2NsName (self, qName, useDefaultNs): + """Convert a qName 'prefix:localName' to a tuple '(namespace, localName)'. + + Input parameter: + qName: qName to be converted + useDefaultNs: 1 if default namespace shall be used + Returns the corresponding tuple '(namespace, localName)' for 'qName'. + """ + if qName != None: + qNamePrefix, qNameLocalName = splitQName (qName) + for prefix, namespaceURI in self.getCurrentNamespaces(): + if qNamePrefix == prefix: + if prefix != EMPTY_PREFIX or useDefaultNs: + nsName = (namespaceURI, qNameLocalName) + break + else: + if qNamePrefix == None: + nsName = (EMPTY_NAMESPACE, qNameLocalName) + else: + raise ValueError, "Namespace prefix '%s' not bound to a namespace!" % (qNamePrefix) + else: + nsName = (None, None) + return NsNameTupleFactory(nsName) + + + def nsName2QName (self, nsLocalName): + """Convert a tuple '(namespace, localName)' to a string 'prefix:localName' + + Input parameter: + nsLocalName: tuple '(namespace, localName)' to be converted + Returns the corresponding string 'prefix:localName' for 'nsLocalName'. + """ + qName = nsNameToQName (nsLocalName, self.getCurrentNamespaces()) + if qName == "xmlns:None": qName = "xmlns" + return qName + + + def getNamespace (self, qName): + """Retrieve namespace for a qName 'prefix:localName'. + + Input parameter: + qName: qName 'prefix:localName' + Returns the corresponding namespace for the prefix of 'qName'. + """ + if qName != None: + qNamePrefix, qNameLocalName = splitQName (qName) + for prefix, namespaceURI in self.getCurrentNamespaces(): + if qNamePrefix == prefix: + namespace = namespaceURI + break + else: + if qNamePrefix == None: + namespace = EMPTY_NAMESPACE + else: + raise LookupError, "Namespace for QName '%s' not found!" % (qName) + else: + namespace = EMPTY_NAMESPACE + return namespace + + + def getNsPrefix (self, nsLocalName): + """Retrieve prefix for a tuple '(namespace, localName)'. + + Input parameter: + nsLocalName: tuple '(namespace, localName)' + Returns the corresponding prefix for the namespace of 'nsLocalName'. + """ + ns = nsLocalName[0] + for prefix, namespace in self.getCurrentNamespaces(): + if ns == namespace: + return prefix + else: + if ns == None: + return None + else: + raise LookupError, "Prefix for namespaceURI '%s' not found!" % (ns) + + +#++++++++++++ limited XPath support ++++++++++++++++++++ + + def getXPath (self, xPath, namespaceRef=None, useDefaultNs=1, attrIgnoreList=[]): + """Retrieve node list or attribute list for specified XPath + + Input parameter: + xPath: string containing xPath specification + namespaceRef: scope for namespaces (default is own element node) + useDefaultNs: 1, if default namespace shall be used if no prefix is available + attrIgnoreList: list of attributes to be ignored if wildcard is specified for attributes + + Returns all nodes which match xPath specification or + list of attribute values if xPath specifies an attribute + """ + return self.getXPathList(xPath, namespaceRef, useDefaultNs, attrIgnoreList)[0] + + + def getXPathList (self, xPath, namespaceRef=None, useDefaultNs=1, attrIgnoreList=[]): + """Retrieve node list or attribute list for specified XPath + + Input parameter: + xPath: string containing xPath specification + namespaceRef: scope for namespaces (default is own element node) + useDefaultNs: 1, if default namespace shall be used if no prefix is available + attrIgnoreList: list of attributes to be ignored if wildcard is specified for attributes + + Returns tuple (completeChildList, attrNodeList, attrNsNameFirst). + completeChildList: contains all child node which match xPath specification or + list of attribute values if xPath specifies an attribute + attrNodeList: contains all child nodes where the specified attribute was found + attrNsNameFirst: contains the name of the first attribute which was found + TODO: Re-design namespace and attribute handling of this method + """ + reChild = re.compile('child *::') + reAttribute = re.compile('attribute *::') + if namespaceRef == None: namespaceRef = self + xPath = reChild.sub('./', xPath) + xPath = reAttribute.sub('@', xPath) + xPathList = string.split (xPath, "|") + completeChildDict = {} + completeChildList = [] + attrNodeList = [] + attrNsNameFirst = None + for xRelPath in xPathList: + xRelPath = string.strip(xRelPath) + descendantOrSelf = 0 + if xRelPath[:3] == ".//": + descendantOrSelf = 1 + xRelPath = xRelPath[3:] + xPathLocalStepList = string.split (xRelPath, "/") + childList = [self, ] + for localStep in xPathLocalStepList: + localStep = string.strip(localStep) + stepChildList = [] + if localStep == "": + raise IOError ("Invalid xPath '%s'!" %(xRelPath)) + elif localStep == ".": + continue + elif localStep[0] == '@': + if len(localStep) == 1: + raise ValueError ("Attribute name is missing in xPath!") + if descendantOrSelf: + childList = self.getElementsByTagName() + attrName = localStep[1:] + for childNode in childList: + if attrName == '*': + attrNodeList.append (childNode) + attrDict = childNode.getAttributeDict() + for attrIgnore in attrIgnoreList: + if attrDict.has_key(attrIgnore): + del attrDict[attrIgnore] + stepChildList.extend(attrDict.values()) + try: + attrNsNameFirst = attrDict.keys()[0] + except: + pass + else: + attrNsName = namespaceRef.qName2NsName (attrName, useDefaultNs=0) + if attrNsName[1] == '*': + for attr in childNode.getAttributeDict().keys(): + if attr[0] == attrNsName[0]: + if attrNodeList == []: + attrNsNameFirst = attrNsName + attrNodeList.append (childNode) + stepChildList.append (childNode.getAttribute(attr)) + elif childNode.hasAttribute(attrNsName): + if attrNodeList == []: + attrNsNameFirst = attrNsName + attrNodeList.append (childNode) + stepChildList.append (childNode.getAttribute(attrNsName)) + childList = stepChildList + else: + nsLocalName = namespaceRef.qName2NsName (localStep, useDefaultNs=useDefaultNs) + if descendantOrSelf: + descendantOrSelf = 0 + if localStep == "*": + stepChildList = self.getElementsByTagName() + else: + stepChildList = self.getElementsByTagName(nsLocalName) + else: + for childNode in childList: + if localStep == "*": + stepChildList.extend (childNode.getChildren()) + else: + stepChildList.extend (childNode.getChildrenNS(nsLocalName[0], nsLocalName[1])) + childList = stepChildList + # filter duplicated childs + for child in childList: + try: + childKey = child.element + except: + childKey = child + if not completeChildDict.has_key(childKey): + completeChildList.append(child) + completeChildDict[childKey] = 1 + return completeChildList, attrNodeList, attrNsNameFirst + + + ############################################################### + # PRIVATE methods + ############################################################### + + def __createElement (self, tupleOrLocalName, attributeDict): + """Create a new ElementWrapper object. + + Input parameter: + tupleOrLocalName: tuple '(namespace, localName)' or 'localName' if no namespace is used + attributeDict: dictionary which contains the attributes and their values of the element node to be created + Returns the created ElementWrapper object + """ + childElementWrapper = self.treeWrapper.createElement (tupleOrLocalName, attributeDict, self.curNs[:]) # TODO: when to be adapted???) + childElementWrapper.element.xmlIfExtSetParentNode(self.element) + return childElementWrapper + + + def __updateAttrMaxLengthDict (self, attrMaxLengthDict): + """Update dictionary which contains the maximum length of node attributes. + + Used for pretty print to align the attributes of child nodes. + attrMaxLengthDict is in/out parameter. + """ + for attrName, attrValue in self.getAttributeDict().items(): + attrLength = len(attrValue) + if not attrMaxLengthDict.has_key(attrName): + attrMaxLengthDict[attrName] = attrLength + else: + attrMaxLengthDict[attrName] = max(attrMaxLengthDict[attrName], attrLength) + + + def __clearChildrenCache (self, childNsName=None): + """Clear children cache. + """ + if self.__useCaching(): + if childNsName != None: + if self.__childrenCache.has_key(childNsName): + del self.__childrenCache[childNsName] + if self.__firstChildCache.has_key(childNsName): + del self.__firstChildCache[childNsName] + else: + self.__childrenCache.clear() + self.__firstChildCache.clear() + + + def __useCaching(self): + return self.treeWrapper.useCaching() + + diff --git a/pymavlink/generator/lib/genxmlif/xmlifBase.py b/pymavlink/generator/lib/genxmlif/xmlifBase.py new file mode 100644 index 0000000..ca2d93f --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmlifBase.py @@ -0,0 +1,130 @@ +# +# genxmlif, Release 0.9.0 +# file: xmlifbase.py +# +# XML interface base classes +# +# history: +# 2005-04-25 rl created +# 2006-08-18 rl some methods for XML schema validation support added +# 2007-05-25 rl performance optimization (caching) added, bugfixes for XPath handling +# 2007-07-04 rl complete re-design, API classes moved to xmlifApi.py +# +# Copyright (c) 2005-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The generic XML interface is +# +# Copyright (c) 2005-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +__author__ = "Roland Leuthe " +__date__ = "28 July 2008" +__version__ = "0.9" + +from xml.dom import XML_NAMESPACE, XMLNS_NAMESPACE +from xmlifUtils import NsNameTupleFactory, convertToAbsUrl + + + +######################################## +# XmlIf builder extension base class +# All not implemented methods have to be overloaded by the derived class!! +# + +class XmlIfBuilderExtensionBase: + """XmlIf builder extension base class. + + This class provides additional data (e.g. line numbers or caches) + for an element node which are stored in the element node object during parsing. + """ + + def __init__ (self, filePath, absUrl, treeWrapper, elementWrapperClass): + """Constructor for this class + + Input parameter: + filePath: contains the file path of the corresponding XML file + absUrl: contains the absolute URL of the corresponding XML file + """ + self.filePath = filePath + self.absUrl = absUrl + self.baseUrlStack = [absUrl, ] + self.treeWrapper = treeWrapper + self.elementWrapperClass = elementWrapperClass + + + def startElementHandler (self, curNode, startLineNumber, curNs, attributes=[]): + """Called by the XML parser at creation of an element node. + + Input parameter: + curNode: current element node + startLineNumber: first line number of the element tag in XML file + curNs: namespaces visible for this element node + attributes: list of attributes and their values for this element node + (same sequence as int he XML file) + """ + + elementWrapper = self.elementWrapperClass(curNode, self.treeWrapper, curNs, initAttrSeq=0) + + elementWrapper.baseUrl = self.__getBaseUrl(elementWrapper) + elementWrapper.absUrl = self.absUrl + elementWrapper.filePath = self.filePath + elementWrapper.startLineNumber = startLineNumber + elementWrapper.curNs.extend ([("xml", XML_NAMESPACE), ("xmlns", XMLNS_NAMESPACE)]) + + if attributes != []: + for i in range (0, len(attributes), 2): + elementWrapper.attributeSequence.append(attributes[i]) + else: + attrList = elementWrapper.getAttributeDict().keys() + attrList.sort() + elementWrapper.attributeSequence.extend (attrList) + + self.baseUrlStack.insert (0, elementWrapper.baseUrl) + + + def endElementHandler (self, curNode, endLineNumber): + """Called by the XML parser after creation of an element node. + + Input parameter: + curNode: current element node + endLineNumber: last line number of the element tag in XML file + """ + curNode.xmlIfExtElementWrapper.endLineNumber = endLineNumber + self.baseUrlStack.pop (0) + + + def __getBaseUrl (self, elementWrapper): + """Retrieve base URL for the given element node. + + Input parameter: + elementWrapper: wrapper of current element node + """ + nsNameBaseAttr = NsNameTupleFactory ((XML_NAMESPACE, "base")) + if elementWrapper.hasAttribute(nsNameBaseAttr): + return convertToAbsUrl (elementWrapper.getAttribute(nsNameBaseAttr), self.baseUrlStack[0]) + else: + return self.baseUrlStack[0] + diff --git a/pymavlink/generator/lib/genxmlif/xmlifDom.py b/pymavlink/generator/lib/genxmlif/xmlifDom.py new file mode 100644 index 0000000..83e357d --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmlifDom.py @@ -0,0 +1,352 @@ +# +# genxmlif, Release 0.9.0 +# file: xmlifDom.py +# +# XML interface base class for Python DOM implementations +# +# history: +# 2005-04-25 rl created +# 2007-07-02 rl complete re-design, internal wrapper +# for DOM trees and elements introduced +# 2008-07-01 rl Limited support of XInclude added +# +# Copyright (c) 2005-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The generic XML interface is +# +# Copyright (c) 2005-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import string +import copy +import urllib +from types import TupleType +from xml.dom import Node, getDOMImplementation, XMLNS_NAMESPACE +from ..genxmlif import XINC_NAMESPACE, GenXmlIfError +from xmlifUtils import nsNameToQName, processWhitespaceAction, collapseString, NsNameTupleFactory, convertToAbsUrl +from xmlifBase import XmlIfBuilderExtensionBase +from xmlifApi import XmlInterfaceBase + + +class XmlInterfaceDom (XmlInterfaceBase): + """Derived interface class for handling of DOM parsers. + + For description of the interface methods see xmlifbase.py. + """ + + def xInclude (self, elementWrapper, baseUrl, ownerDoc): + filePath = elementWrapper.getFilePath() + for childElementWrapper in elementWrapper.getChildren(): + line = childElementWrapper.getStartLineNumber() + if childElementWrapper.getNsName() == (XINC_NAMESPACE, "include"): + href = childElementWrapper["href"] + parse = childElementWrapper.getAttributeOrDefault ("parse", "xml") + encoding = childElementWrapper.getAttribute ("encoding") + if self.verbose: + print "Xinclude: %s" %href + try: + if parse == "xml": + subTreeWrapper = self.parse (href, baseUrl, ownerDoc) + elementWrapper.replaceChildBySubtree (childElementWrapper, subTreeWrapper) + elif parse == "text": + absUrl = convertToAbsUrl (href, baseUrl) + fp = urllib.urlopen (absUrl) + data = fp.read() + if encoding: + data = data.decode(encoding) + newTextNode = ownerDoc.xmlIfExtCreateTextNode(data) + elementWrapper.element.element.insertBefore (newTextNode, childElementWrapper.element.element) + elementWrapper.removeChild (childElementWrapper) + fp.close() + else: + raise GenXmlIfError, "%s: line %s: XIncludeError: Invalid 'parse' Attribut: '%s'" %(filePath, line, parse) + except IOError, errInst: + raise GenXmlIfError, "%s: line %s: IOError: %s" %(filePath, line, str(errInst)) + elif childElementWrapper.getNsName() == (XINC_NAMESPACE, "fallback"): + raise GenXmlIfError, "%s: line %s: XIncludeError: xi:fallback tag must be child of xi:include" %(filePath, line) + else: + self.xInclude(childElementWrapper, baseUrl, ownerDoc) + + + +class InternalDomTreeWrapper: + """Internal wrapper for a DOM Document class. + """ + def __init__ (self, document): + self.document = document + + def xmlIfExtGetRootNode (self): + domNode = self.document + if domNode.nodeType == Node.DOCUMENT_NODE: + return domNode.documentElement.xmlIfExtInternalWrapper + elif domNode.nodeType == Node.DOCUMENT_FRAGMENT_NODE: + for node in domNode.childNodes: + if node.nodeType == Node.ELEMENT_NODE: + return node.xmlIfExtInternalWrapper + else: + return None + else: + return None + + + def xmlIfExtCreateElement (self, nsName, attributeDict, curNs): + elementNode = self.document.createElementNS (nsName[0], nsName[1]) + intElementWrapper = self.internalElementWrapperClass(elementNode, self) + for attrName, attrValue in attributeDict.items(): + intElementWrapper.xmlIfExtSetAttribute (NsNameTupleFactory(attrName), attrValue, curNs) + return intElementWrapper + + + def xmlIfExtCreateTextNode (self, data): + return self.document.createTextNode(data) + + + def xmlIfExtImportNode (self, node): + return self.document.importNode (node, 0) + + + def xmlIfExtCloneTree (self, rootElementCopy): + domImpl = getDOMImplementation() +# documentCopy = domImpl.createDocument(rootElementCopy.xmlIfExtGetNamespaceURI(), rootElementCopy.xmlIfExtGetTagName(), None) + documentCopy = domImpl.createDocument(None, None, None) +# documentCopy = copy.copy(self.document) + documentCopy.documentElement = rootElementCopy.element + return self.__class__(documentCopy) + + + +######################################################### +# Internal Wrapper class for a Dom Element class + +class InternalDomElementWrapper: + """Internal Wrapper for a Dom Element class. + """ + + def __init__ (self, element, internalDomTreeWrapper): + self.element = element + element.xmlIfExtInternalWrapper = self + self.internalDomTreeWrapper = internalDomTreeWrapper + + + def xmlIfExtUnlink (self): + self.xmlIfExtElementWrapper = None + + + def xmlIfExtCloneNode (self): + nodeCopy = self.__class__(self.element.cloneNode(deep=0), self.internalDomTreeWrapper) + for childTextNode in self.__xmlIfExtGetChildTextNodes(): + childTextNodeCopy = childTextNode.cloneNode(0) + nodeCopy.element.appendChild (childTextNodeCopy) +# for nsAttrName, attrValue in self.xmlIfExtGetAttributeDict().items(): +# nodeCopy.xmlIfExtSetAttribute(nsAttrName, attrValue, self.xmlIfExtElementWrapper.getCurrentNamespaces()) + return nodeCopy + + + def xmlIfExtGetTagName (self): + return self.element.tagName + + + def xmlIfExtGetNamespaceURI (self): + return self.element.namespaceURI + + + def xmlIfExtGetParentNode (self): + parentNode = self.element.parentNode + if parentNode.nodeType == Node.ELEMENT_NODE: + return self.element.parentNode.xmlIfExtInternalWrapper + else: + return None + + + def xmlIfExtSetParentNode (self, parentElement): + pass # nothing to do since parent is provided by DOM interface + + + def xmlIfExtGetChildren (self, tagFilter=None): + # TODO: Handle also wildcard tagFilter = (namespace, None) + children = filter (lambda e: (e.nodeType == Node.ELEMENT_NODE) and # - only ELEMENTs + (tagFilter == None or + (e.namespaceURI == tagFilter[0] and e.localName == tagFilter[1])), # - if tagFilter given --> check + self.element.childNodes ) # from element's nodes + + return map(lambda element: element.xmlIfExtInternalWrapper, children) + + + def xmlIfExtGetFirstChild (self, tagFilter=None): + children = self.xmlIfExtGetChildren (tagFilter) + if children != []: + return children[0] + else: + None + + + def xmlIfExtGetElementsByTagName (self, tagFilter=('*','*')): + elementList = self.element.getElementsByTagNameNS( tagFilter[0], tagFilter[1] ) + return map( lambda element: element.xmlIfExtInternalWrapper, elementList ) + + + def xmlIfExtGetIterator (self, tagFilter=('*','*')): + elementList = [] + if tagFilter in (('*','*'), (self.element.namespaceURI, self.element.localName)): + elementList.append(self.element) + elementList.extend(self.element.getElementsByTagNameNS( tagFilter[0], tagFilter[1] )) + return map( lambda element: element.xmlIfExtInternalWrapper, elementList ) + + + def xmlIfExtAppendChild (self, childElement): + self.element.appendChild (childElement.element) + + + def xmlIfExtInsertBefore (self, childElement, refChildElement): + self.element.insertBefore (childElement.element, refChildElement.element) + + + def xmlIfExtRemoveChild (self, childElement): + self.element.removeChild (childElement.element) + + + def xmlIfExtInsertSubtree (self, refChildElement, subTree, insertSubTreeRootNode): + if insertSubTreeRootNode: + childElementList = [subTree.xmlIfExtGetRootNode(),] + else: + childElementList = subTree.xmlIfExtGetRootNode().xmlIfExtGetChildren() + + for childElement in childElementList: + if refChildElement != None: + self.element.insertBefore(childElement.element, refChildElement.element) + else: + self.element.appendChild(childElement.element) + + + def xmlIfExtGetAttributeDict (self): + attribDict = {} + for nsAttrName, attrNodeOrValue in self.element.attributes.items(): + attribDict[NsNameTupleFactory(nsAttrName)] = attrNodeOrValue.nodeValue + return attribDict + + + def xmlIfExtGetAttribute (self, nsAttrName): + if self.element.attributes.has_key (nsAttrName): + return self.element.getAttributeNS (nsAttrName[0], nsAttrName[1]) + elif nsAttrName[1] == "xmlns" and self.element.attributes.has_key(nsAttrName[1]): + # workaround for minidom for correct access of xmlns attribute + return self.element.getAttribute (nsAttrName[1]) + else: + return None + + + def xmlIfExtSetAttribute (self, nsAttrName, attributeValue, curNs): + if nsAttrName[0] != None: + qName = nsNameToQName (nsAttrName, curNs) + else: + qName = nsAttrName[1] + + self.element.setAttributeNS (nsAttrName[0], qName, attributeValue) + + + def xmlIfExtRemoveAttribute (self, nsAttrName): + self.element.removeAttributeNS (nsAttrName[0], nsAttrName[1]) + + + def xmlIfExtGetElementValueFragments (self, ignoreEmtpyStringFragments): + elementValueList = [] + for childTextNode in self.__xmlIfExtGetChildTextNodes(): + elementValueList.append(childTextNode.data) + if ignoreEmtpyStringFragments: + elementValueList = filter (lambda s: collapseString(s) != "", elementValueList) + if elementValueList == []: + elementValueList = ["",] + return elementValueList + + + def xmlIfExtGetElementText (self): + elementTextList = ["",] + if self.element.childNodes != []: + for childNode in self.element.childNodes: + if childNode.nodeType in (Node.TEXT_NODE, Node.CDATA_SECTION_NODE): + elementTextList.append (childNode.data) + else: + break + return "".join(elementTextList) + + + def xmlIfExtGetElementTailText (self): + tailTextList = ["",] + nextSib = self.element.nextSibling + while nextSib: + if nextSib.nodeType in (Node.TEXT_NODE, Node.CDATA_SECTION_NODE): + tailTextList.append (nextSib.data) + nextSib = nextSib.nextSibling + else: + break + return "".join(tailTextList) + + + def xmlIfExtSetElementValue (self, elementValue): + if self.__xmlIfExtGetChildTextNodes() == []: + textNode = self.internalDomTreeWrapper.xmlIfExtCreateTextNode (elementValue) + self.element.appendChild (textNode) + else: + self.__xmlIfExtGetChildTextNodes()[0].data = elementValue + if len (self.__xmlIfExtGetChildTextNodes()) > 1: + for textNode in self.__xmlIfExtGetChildTextNodes()[1:]: + textNode.data = "" + + + def xmlIfExtProcessWsElementValue (self, wsAction): + textNodes = self.__xmlIfExtGetChildTextNodes() + + if len(textNodes) == 1: + textNodes[0].data = processWhitespaceAction (textNodes[0].data, wsAction) + elif len(textNodes) > 1: + textNodes[0].data = processWhitespaceAction (textNodes[0].data, wsAction, rstrip=0) + lstrip = 0 + if len(textNodes[0].data) > 0 and textNodes[0].data[-1] == " ": + lstrip = 1 + for textNode in textNodes[1:-1]: + textNode.data = processWhitespaceAction (textNode.data, wsAction, lstrip, rstrip=0) + if len(textNode.data) > 0 and textNode.data[-1] == " ": + lstrip = 1 + else: + lstrip = 0 + textNodes[-1].data = processWhitespaceAction (textNodes[-1].data, wsAction, lstrip) + + + ############################################################### + # PRIVATE methods + ############################################################### + + def __xmlIfExtGetChildTextNodes ( self ): + """Return list of TEXT nodes.""" + return filter (lambda e: ( e.nodeType in (Node.TEXT_NODE, Node.CDATA_SECTION_NODE) ), # - only TEXT-NODES + self.element.childNodes) # from element's child nodes + + + +class XmlIfBuilderExtensionDom (XmlIfBuilderExtensionBase): + """XmlIf builder extension class for DOM parsers.""" + + pass diff --git a/pymavlink/generator/lib/genxmlif/xmlifElementTree.py b/pymavlink/generator/lib/genxmlif/xmlifElementTree.py new file mode 100644 index 0000000..4e49da8 --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmlifElementTree.py @@ -0,0 +1,407 @@ +# +# genxmlif, Release 0.9.0 +# file: xmlifElementTree.py +# +# XML interface class to elementtree toolkit by Fredrik Lundh +# +# history: +# 2005-04-25 rl created +# 2007-05-25 rl performance optimization (caching) added, some bugfixes +# 2007-06-29 rl complete re-design, ElementExtension class introduced +# 2008-07-01 rl Limited support of XInclude added +# +# Copyright (c) 2005-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The generic XML interface is +# +# Copyright (c) 2005-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import sys +import string +import urllib +from xml.dom import EMPTY_NAMESPACE, XMLNS_NAMESPACE +from xml.parsers.expat import ExpatError +# from version 2.5 on the elementtree module is part of the standard python distribution +if sys.version_info[:2] >= (2,5): + from xml.etree.ElementTree import ElementTree, _ElementInterface, XMLTreeBuilder, TreeBuilder + from xml.etree import ElementInclude +else: + from elementtree.ElementTree import ElementTree, _ElementInterface, XMLTreeBuilder, TreeBuilder + from elementtree import ElementInclude +from ..genxmlif import XMLIF_ELEMENTTREE, GenXmlIfError +from xmlifUtils import convertToAbsUrl, processWhitespaceAction, collapseString, toClarkQName, splitQName +from xmlifBase import XmlIfBuilderExtensionBase +from xmlifApi import XmlInterfaceBase + +######################################################### +# Derived interface class for elementtree toolkit + +class XmlInterfaceElementTree (XmlInterfaceBase): + ##################################################### + # for description of the interface methods see xmlifbase.py + ##################################################### + + def __init__ (self, verbose, useCaching, processXInclude): + XmlInterfaceBase.__init__ (self, verbose, useCaching, processXInclude) + self.xmlIfType = XMLIF_ELEMENTTREE + if self.verbose: + print "Using elementtree interface module..." + + + def createXmlTree (self, namespace, xmlRootTagName, attributeDict={}, publicId=None, systemId=None): + rootNode = ElementExtension(toClarkQName(xmlRootTagName), attributeDict) + rootNode.xmlIfExtSetParentNode(None) + treeWrapper = self.treeWrapperClass(self, ElementTreeExtension(rootNode), self.useCaching) + rootNodeWrapper = self.elementWrapperClass (rootNode, treeWrapper, []) # TODO: namespace handling + return treeWrapper + + + def parse (self, file, baseUrl="", ownerDoc=None): + absUrl = convertToAbsUrl (file, baseUrl) + fp = urllib.urlopen (absUrl) + try: + tree = ElementTreeExtension() + treeWrapper = self.treeWrapperClass(self, tree, self.useCaching) + parser = ExtXMLTreeBuilder(file, absUrl, self, treeWrapper) + treeWrapper.getTree().parse(fp, parser) + fp.close() + + # XInclude support + if self.processXInclude: + loaderInst = ExtXIncludeLoader (self.parse, absUrl, ownerDoc) + try: + ElementInclude.include(treeWrapper.getTree().getroot(), loaderInst.loader) + except IOError, errInst: + raise GenXmlIfError, "%s: IOError: %s" %(file, str(errInst)) + + except ExpatError, errstr: + fp.close() + raise GenXmlIfError, "%s: ExpatError: %s" %(file, str(errstr)) + except ElementInclude.FatalIncludeError, errInst: + fp.close() + raise GenXmlIfError, "%s: XIncludeError: %s" %(file, str(errInst)) + + return treeWrapper + + + def parseString (self, text, baseUrl="", ownerDoc=None): + absUrl = convertToAbsUrl ("", baseUrl) + tree = ElementTreeExtension() + treeWrapper = self.treeWrapperClass(self, tree, self.useCaching) + parser = ExtXMLTreeBuilder("", absUrl, self, treeWrapper) + parser.feed(text) + treeWrapper.getTree()._setroot(parser.close()) + + # XInclude support + if self.processXInclude: + loaderInst = ExtXIncludeLoader (self.parse, absUrl, ownerDoc) + ElementInclude.include(treeWrapper.getTree().getroot(), loaderInst.loader) + + return treeWrapper + + +######################################################### +# Extension (derived) class for ElementTree class + +class ElementTreeExtension (ElementTree): + + def xmlIfExtGetRootNode (self): + return self.getroot() + + + def xmlIfExtCreateElement (self, nsName, attributeDict, curNs): + clarkQName = toClarkQName(nsName) + return ElementExtension (clarkQName, attributeDict) + + + def xmlIfExtCloneTree (self, rootElementCopy): + return self.__class__(element=rootElementCopy) + + +######################################################### +# Wrapper class for Element class + +class ElementExtension (_ElementInterface): + + def __init__ (self, xmlRootTagName, attributeDict): + _ElementInterface.__init__(self, xmlRootTagName, attributeDict) + + + def xmlIfExtUnlink (self): + self.xmlIfExtElementWrapper = None + self.__xmlIfExtParentElement = None + + + def xmlIfExtCloneNode (self): + nodeCopy = self.__class__(self.tag, self.attrib.copy()) + nodeCopy.text = self.text + nodeCopy.tail = self.tail + return nodeCopy + + + def xmlIfExtGetTagName (self): + return self.tag + + + def xmlIfExtGetNamespaceURI (self): + prefix, localName = splitQName(self.tag) + return prefix + + + def xmlIfExtGetParentNode (self): + return self.__xmlIfExtParentElement + + + def xmlIfExtSetParentNode (self, parentElement): + self.__xmlIfExtParentElement = parentElement + + + def xmlIfExtGetChildren (self, filterTag=None): + if filterTag == None: + return self.getchildren() + else: + clarkFilterTag = toClarkQName(filterTag) + return self.findall(clarkFilterTag) + + + def xmlIfExtGetFirstChild (self, filterTag=None): + # replace base method (performance optimized) + if filterTag == None: + children = self.getchildren() + if children != []: + element = children[0] + else: + element = None + else: + clarkFilterTag = toClarkQName(filterTag) + element = self.find(clarkFilterTag) + + return element + + + def xmlIfExtGetElementsByTagName (self, filterTag=(None,None)): + clarkFilterTag = toClarkQName(filterTag) + descendants = [] + for node in self.xmlIfExtGetChildren(): + descendants.extend(node.getiterator(clarkFilterTag)) + return descendants + + + def xmlIfExtGetIterator (self, filterTag=(None,None)): + clarkFilterTag = toClarkQName(filterTag) + return self.getiterator (clarkFilterTag) + + + def xmlIfExtAppendChild (self, childElement): + self.append (childElement) + childElement.xmlIfExtSetParentNode(self) + + + def xmlIfExtInsertBefore (self, childElement, refChildElement): + self.insert (self.getchildren().index(refChildElement), childElement) + childElement.xmlIfExtSetParentNode(self) + + + def xmlIfExtRemoveChild (self, childElement): + self.remove (childElement) + + + def xmlIfExtInsertSubtree (self, refChildElement, subTree, insertSubTreeRootNode): + if refChildElement != None: + insertIndex = self.getchildren().index (refChildElement) + else: + insertIndex = 0 + if insertSubTreeRootNode: + elementList = [subTree.xmlIfExtGetRootNode(),] + else: + elementList = subTree.xmlIfExtGetRootNode().xmlIfExtGetChildren() + elementList.reverse() + for element in elementList: + self.insert (insertIndex, element) + element.xmlIfExtSetParentNode(self) + + + def xmlIfExtGetAttributeDict (self): + attrDict = {} + for attrName, attrValue in self.attrib.items(): + namespaceEndIndex = string.find (attrName, '}') + if namespaceEndIndex != -1: + attrName = (attrName[1:namespaceEndIndex], attrName[namespaceEndIndex+1:]) + else: + attrName = (EMPTY_NAMESPACE, attrName) + attrDict[attrName] = attrValue + return attrDict + + + def xmlIfExtGetAttribute (self, tupleOrAttrName): + clarkQName = toClarkQName(tupleOrAttrName) + if self.attrib.has_key(clarkQName): + return self.attrib[clarkQName] + else: + return None + + + def xmlIfExtSetAttribute (self, tupleOrAttrName, attributeValue, curNs): + self.attrib[toClarkQName(tupleOrAttrName)] = attributeValue + + + def xmlIfExtRemoveAttribute (self, tupleOrAttrName): + clarkQName = toClarkQName(tupleOrAttrName) + if self.attrib.has_key(clarkQName): + del self.attrib[clarkQName] + + + def xmlIfExtGetElementValueFragments (self, ignoreEmtpyStringFragments): + elementValueList = [] + if self.text != None: + elementValueList.append(self.text) + for child in self.getchildren(): + if child.tail != None: + elementValueList.append(child.tail) + if ignoreEmtpyStringFragments: + elementValueList = filter (lambda s: collapseString(s) != "", elementValueList) + if elementValueList == []: + elementValueList = ["",] + return elementValueList + + + def xmlIfExtGetElementText (self): + if self.text != None: + return self.text + else: + return "" + + + def xmlIfExtGetElementTailText (self): + if self.tail != None: + return self.tail + else: + return "" + + + def xmlIfExtSetElementValue (self, elementValue): + self.text = elementValue + for child in self.getchildren(): + child.tail = None + + + def xmlIfExtProcessWsElementValue (self, wsAction): + noOfTextFragments = reduce(lambda sum, child: sum + (child.tail != None), self.getchildren(), 0) + noOfTextFragments += (self.text != None) + + rstrip = 0 + lstrip = 1 + if self.text != None: + if noOfTextFragments == 1: + rstrip = 1 + self.text = processWhitespaceAction (self.text, wsAction, lstrip, rstrip) + noOfTextFragments -= 1 + lstrip = 0 + for child in self.getchildren(): + if child.tail != None: + if noOfTextFragments == 1: + rstrip = 1 + child.tail = processWhitespaceAction (child.tail, wsAction, lstrip, rstrip) + noOfTextFragments -= 1 + lstrip = 0 + + +################################################### +# Element tree builder class derived from XMLTreeBuilder +# extended to store related line numbers in the Element object + +class ExtXMLTreeBuilder (XMLTreeBuilder, XmlIfBuilderExtensionBase): + def __init__(self, filePath, absUrl, xmlIf, treeWrapper): + XMLTreeBuilder.__init__(self, target=TreeBuilder(element_factory=ElementExtension)) + self._parser.StartNamespaceDeclHandler = self._start_ns + self._parser.EndNamespaceDeclHandler = self._end_ns + self.namespaces = [] + XmlIfBuilderExtensionBase.__init__(self, filePath, absUrl, treeWrapper, xmlIf.elementWrapperClass) + + def _start(self, tag, attrib_in): + elem = XMLTreeBuilder._start(self, tag, attrib_in) + self.start(elem) + + def _start_list(self, tag, attrib_in): + elem = XMLTreeBuilder._start_list(self, tag, attrib_in) + self.start(elem, attrib_in) + + def _end(self, tag): + elem = XMLTreeBuilder._end(self, tag) + self.end(elem) + + def _start_ns(self, prefix, value): + self.namespaces.insert(0, (prefix, value)) + + def _end_ns(self, prefix): + assert self.namespaces.pop(0)[0] == prefix, "implementation confused" + + + def start(self, element, attributes): + # bugfix for missing start '{' + for i in range (0, len(attributes), 2): + attrName = attributes[i] + namespaceEndIndex = string.find (attrName, '}') + if namespaceEndIndex != -1 and attrName[0] != "{": + attributes[i] = '{' + attributes[i] + # bugfix end + + XmlIfBuilderExtensionBase.startElementHandler (self, element, self._parser.ErrorLineNumber, self.namespaces[:], attributes) + if len(self._target._elem) > 1: + element.xmlIfExtSetParentNode (self._target._elem[-2]) + else: + for namespace in self.namespaces: + if namespace[1] != None: + element.xmlIfExtElementWrapper.setAttribute((XMLNS_NAMESPACE, namespace[0]), namespace[1]) + + + def end(self, element): + XmlIfBuilderExtensionBase.endElementHandler (self, element, self._parser.ErrorLineNumber) + + +################################################### +# XInclude loader +# + +class ExtXIncludeLoader: + + def __init__(self, parser, baseUrl, ownerDoc): + self.parser = parser + self.baseUrl = baseUrl + self.ownerDoc = ownerDoc + + def loader(self, href, parse, encoding=None): + if parse == "xml": + data = self.parser(href, self.baseUrl, self.ownerDoc).getTree().getroot() + else: + absUrl = convertToAbsUrl (href, self.baseUrl) + fp = urllib.urlopen (absUrl) + data = fp.read() + if encoding: + data = data.decode(encoding) + fp.close() + return data diff --git a/pymavlink/generator/lib/genxmlif/xmlifMinidom.py b/pymavlink/generator/lib/genxmlif/xmlifMinidom.py new file mode 100644 index 0000000..036ac6c --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmlifMinidom.py @@ -0,0 +1,198 @@ +# +# genxmlif, Release 0.9.0 +# file: xmlifMinidom.py +# +# XML interface class to Python standard minidom +# +# history: +# 2005-04-25 rl created +# 2007-07-02 rl complete re-design, internal wrapper +# for DOM trees and elements introduced +# 2008-07-01 rl Limited support of XInclude added +# +# Copyright (c) 2005-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The generix XML interface is +# +# Copyright (c) 2005-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import string +import urllib +from xml.dom import Node, XMLNS_NAMESPACE +from xml.dom.expatbuilder import ExpatBuilderNS +from xml.parsers.expat import ExpatError +from ..genxmlif import XMLIF_MINIDOM, GenXmlIfError +from xmlifUtils import convertToAbsUrl, NsNameTupleFactory +from xmlifDom import XmlInterfaceDom, InternalDomTreeWrapper, InternalDomElementWrapper, XmlIfBuilderExtensionDom + + +class XmlInterfaceMinidom (XmlInterfaceDom): + """Derived interface class for handling of minidom parser. + + For description of the interface methods see xmlifbase.py. + """ + + def __init__ (self, verbose, useCaching, processXInclude): + XmlInterfaceDom.__init__ (self, verbose, useCaching, processXInclude) + self.xmlIfType = XMLIF_MINIDOM + if self.verbose: + print "Using minidom interface module..." + + + def createXmlTree (self, namespace, xmlRootTagName, attributeDict={}, publicId=None, systemId=None): + from xml.dom.minidom import getDOMImplementation + domImpl = getDOMImplementation() + doctype = domImpl.createDocumentType(xmlRootTagName, publicId, systemId) + domTree = domImpl.createDocument(namespace, xmlRootTagName, doctype) + treeWrapper = self.treeWrapperClass(self, InternalMinidomTreeWrapper(domTree), self.useCaching) + + intRootNodeWrapper = InternalMinidomElementWrapper(domTree.documentElement, treeWrapper.getTree()) + rootNodeWrapper = self.elementWrapperClass (intRootNodeWrapper, treeWrapper, []) # TODO: namespace handling + for attrName, attrValue in attributeDict.items(): + rootNodeWrapper.setAttribute (attrName, attrValue) + + return treeWrapper + + + def parse (self, file, baseUrl="", internalOwnerDoc=None): + absUrl = convertToAbsUrl(file, baseUrl) + fp = urllib.urlopen (absUrl) + try: + builder = ExtExpatBuilderNS(file, absUrl, self) + tree = builder.parseFile(fp) + + # XInclude support + if self.processXInclude: + if internalOwnerDoc == None: + internalOwnerDoc = builder.treeWrapper.getTree() + self.xInclude (builder.treeWrapper.getRootNode(), absUrl, internalOwnerDoc) + + fp.close() + except ExpatError, errInst: + fp.close() + raise GenXmlIfError, "%s: ExpatError: %s" %(file, str(errInst)) + + return builder.treeWrapper + + + def parseString (self, text, baseUrl="", internalOwnerDoc=None): + absUrl = convertToAbsUrl ("", baseUrl) + try: + builder = ExtExpatBuilderNS("", absUrl, self) + builder.parseString (text) + + # XInclude support + if self.processXInclude: + if internalOwnerDoc == None: + internalOwnerDoc = builder.treeWrapper.getTree() + self.xInclude (builder.treeWrapper.getRootNode(), absUrl, internalOwnerDoc) + except ExpatError, errInst: + raise GenXmlIfError, "%s: ExpatError: %s" %(baseUrl, str(errInst)) + + return builder.treeWrapper + + + +class InternalMinidomTreeWrapper (InternalDomTreeWrapper): + """Internal wrapper for a minidom Document class. + """ + + def __init__ (self, document): + InternalDomTreeWrapper.__init__(self, document) + self.internalElementWrapperClass = InternalMinidomElementWrapper + + + +class InternalMinidomElementWrapper (InternalDomElementWrapper): + """Internal Wrapper for a Dom Element class. + """ + + def xmlIfExtGetAttributeDict (self): + """Return a dictionary with all attributes of this element.""" + attribDict = {} + for attrNameNS, attrNodeOrValue in self.element.attributes.itemsNS(): + attribDict[NsNameTupleFactory(attrNameNS)] = attrNodeOrValue + + return attribDict + + + +class ExtExpatBuilderNS (ExpatBuilderNS, XmlIfBuilderExtensionDom): + """Extended Expat Builder class derived from ExpatBuilderNS. + + Extended to store related line numbers, file/URL names and + defined namespaces in the node object. + """ + + def __init__ (self, filePath, absUrl, xmlIf): + ExpatBuilderNS.__init__(self) + internalMinidomTreeWrapper = InternalMinidomTreeWrapper(self.document) + self.treeWrapper = xmlIf.treeWrapperClass(self, internalMinidomTreeWrapper, xmlIf.useCaching) + XmlIfBuilderExtensionDom.__init__(self, filePath, absUrl, self.treeWrapper, xmlIf.elementWrapperClass) + + # set EndNamespaceDeclHandler, currently not used by minidom + self.getParser().EndNamespaceDeclHandler = self.end_namespace_decl_handler + self.curNamespaces = [] + + + def start_element_handler(self, name, attributes): + ExpatBuilderNS.start_element_handler(self, name, attributes) + + # use attribute format {namespace}localName + attrList = [] + for i in range (0, len(attributes), 2): + attrName = attributes[i] + attrNameSplit = string.split(attrName, " ") + if len(attrNameSplit) > 1: + attrName = (attrNameSplit[0], attrNameSplit[1]) + attrList.extend([attrName, attributes[i+1]]) + + internalMinidomElementWrapper = InternalMinidomElementWrapper(self.curNode, self.treeWrapper.getTree()) + XmlIfBuilderExtensionDom.startElementHandler (self, internalMinidomElementWrapper, self.getParser().ErrorLineNumber, self.curNamespaces[:], attrList) + + if self.curNode.parentNode.nodeType == Node.DOCUMENT_NODE: + for namespace in self.curNamespaces: + if namespace[0] != None: + internalMinidomElementWrapper.xmlIfExtElementWrapper.attributeSequence.append((XMLNS_NAMESPACE, namespace[0])) + else: + internalMinidomElementWrapper.xmlIfExtElementWrapper.attributeSequence.append("xmlns") +# internalMinidomElementWrapper.xmlIfExtElementWrapper.setAttribute((XMLNS_NAMESPACE, namespace[0]), namespace[1]) + + + def end_element_handler(self, name): + XmlIfBuilderExtensionDom.endElementHandler (self, self.curNode.xmlIfExtInternalWrapper, self.getParser().ErrorLineNumber) + ExpatBuilderNS.end_element_handler(self, name) + + + def start_namespace_decl_handler(self, prefix, uri): + ExpatBuilderNS.start_namespace_decl_handler(self, prefix, uri) + self.curNamespaces.insert(0, (prefix, uri)) + + + def end_namespace_decl_handler(self, prefix): + assert self.curNamespaces.pop(0)[0] == prefix, "implementation confused" + diff --git a/pymavlink/generator/lib/genxmlif/xmlifODict.py b/pymavlink/generator/lib/genxmlif/xmlifODict.py new file mode 100644 index 0000000..ca10b04 --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmlifODict.py @@ -0,0 +1,57 @@ +from types import DictType +from UserDict import UserDict + +class odict(UserDict): + def __init__(self, dictOrTuple = None): + self._keys = [] + UserDict.__init__(self, dictOrTuple) + + def __delitem__(self, key): + UserDict.__delitem__(self, key) + self._keys.remove(key) + + def __setitem__(self, key, item): + UserDict.__setitem__(self, key, item) + if key not in self._keys: self._keys.append(key) + + def clear(self): + UserDict.clear(self) + self._keys = [] + + def copy(self): + newInstance = odict() + newInstance.update(self) + return newInstance + + def items(self): + return zip(self._keys, self.values()) + + def keys(self): + return self._keys[:] + + def popitem(self): + try: + key = self._keys[-1] + except IndexError: + raise KeyError('dictionary is empty') + + val = self[key] + del self[key] + + return (key, val) + + def setdefault(self, key, failobj = None): + if key not in self._keys: + self._keys.append(key) + return UserDict.setdefault(self, key, failobj) + + def update(self, dictOrTuple): + if isinstance(dictOrTuple, DictType): + itemList = dictOrTuple.items() + else: + itemList = dictOrTuple + for key, val in itemList: + self.__setitem__(key,val) + + def values(self): + return map(self.get, self._keys) \ No newline at end of file diff --git a/pymavlink/generator/lib/genxmlif/xmlifUtils.py b/pymavlink/generator/lib/genxmlif/xmlifUtils.py new file mode 100644 index 0000000..f452dd1 --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmlifUtils.py @@ -0,0 +1,374 @@ +# +# genxmlif, Release 0.9.0 +# file: xmlifUtils.py +# +# utility module for genxmlif +# +# history: +# 2005-04-25 rl created +# 2008-08-01 rl encoding support added +# +# Copyright (c) 2005-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The generic XML interface is +# +# Copyright (c) 2005-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import string +import re +import os +import urllib +import urlparse +from types import StringTypes, TupleType +from xml.dom import EMPTY_PREFIX, EMPTY_NAMESPACE + +###################################################################### +# DEFINITIONS +###################################################################### + +###################################################################### +# REGULAR EXPRESSION OBJECTS +###################################################################### + +_reWhitespace = re.compile('\s') +_reWhitespaces = re.compile('\s+') + +_reSplitUrlApplication = re.compile (r"(file|http|ftp|gopher):(.+)") # "file:///d:\test.xml" => "file" + "///d:\test.xml" + + +###################################################################### +# FUNCTIONS +###################################################################### + + +######################################## +# remove all whitespaces from a string +# +def removeWhitespaces (strValue): + return _reWhitespaces.sub('', strValue) + + +######################################## +# substitute multiple whitespace characters by a single ' ' +# +def collapseString (strValue, lstrip=1, rstrip=1): + collStr = _reWhitespaces.sub(' ', strValue) + if lstrip and rstrip: + return collStr.strip() + elif lstrip: + return collStr.lstrip() + elif rstrip: + return collStr.rstrip() + else: + return collStr + + + +######################################## +# substitute each whitespace characters by a single ' ' +# +def normalizeString (strValue): + return _reWhitespace.sub(' ', strValue) + + +######################################## +# process whitespace action +# +def processWhitespaceAction (strValue, wsAction, lstrip=1, rstrip=1): + if wsAction == "collapse": + return collapseString(strValue, lstrip, rstrip) + elif wsAction == "replace": + return normalizeString(strValue) + else: + return strValue + + +########################################################## +# convert input parameter 'fileOrUrl' into a valid URL + +def convertToUrl (fileOrUrl): + matchObject = _reSplitUrlApplication.match(fileOrUrl) + if matchObject: + # given fileOrUrl is an absolute URL + if matchObject.group(1) == 'file': + path = re.sub(':', '|', matchObject.group(2)) # replace ':' by '|' in the path string + url = "file:" + path + else: + url = fileOrUrl + elif not os.path.isfile(fileOrUrl): + # given fileOrUrl is treated as a relative URL + url = fileOrUrl + else: + # local filename +# url = "file:" + urllib.pathname2url (fileOrUrl) + url = urllib.pathname2url (fileOrUrl) + + return url + + +########################################################## +# convert input parameter 'fileOrUrl' into a valid absolute URL + +def convertToAbsUrl (fileOrUrl, baseUrl): + if fileOrUrl == "" and baseUrl != "": + absUrl = "file:" + urllib.pathname2url (os.path.join(os.getcwd(), baseUrl, "__NO_FILE__")) + elif os.path.isfile(fileOrUrl): + absUrl = "file:" + urllib.pathname2url (os.path.join(os.getcwd(), fileOrUrl)) + else: + matchObject = _reSplitUrlApplication.match(fileOrUrl) + if matchObject: + # given fileOrUrl is an absolute URL + if matchObject.group(1) == 'file': + path = re.sub(':', '|', matchObject.group(2)) # replace ':' by '|' in the path string + absUrl = "file:" + path + else: + absUrl = fileOrUrl + else: + # given fileOrUrl is treated as a relative URL + if baseUrl != "": + absUrl = urlparse.urljoin (baseUrl, fileOrUrl) + else: + absUrl = fileOrUrl +# raise IOError, "File %s not found!" %(fileOrUrl) + return absUrl + + +########################################################## +# normalize filter +def normalizeFilter (filterVar): + if filterVar == None or filterVar == '*': + filterVar = ("*",) + elif not isinstance(filterVar, TupleType): + filterVar = (filterVar,) + return filterVar + + +###################################################################### +# Namespace handling +###################################################################### + +def nsNameToQName (nsLocalName, curNs): + """Convert a tuple '(namespace, localName)' to a string 'prefix:localName' + + Input parameter: + nsLocalName: tuple '(namespace, localName)' to be converted + curNs: list of current namespaces + Returns the corresponding string 'prefix:localName' for 'nsLocalName'. + """ + ns = nsLocalName[0] + for prefix, namespace in curNs: + if ns == namespace: + if prefix != None: + return "%s:%s" %(prefix, nsLocalName[1]) + else: + return "%s" %nsLocalName[1] + else: + if ns == None: + return nsLocalName[1] + else: + raise LookupError, "Prefix for namespaceURI '%s' not found!" % (ns) + + +def splitQName (qName): + """Split the given 'qName' into prefix/namespace and local name. + + Input parameter: + 'qName': contains a string 'prefix:localName' or '{namespace}localName' + Returns a tuple (prefixOrNamespace, localName) + """ + namespaceEndIndex = string.find (qName, '}') + if namespaceEndIndex != -1: + prefix = qName[1:namespaceEndIndex] + localName = qName[namespaceEndIndex+1:] + else: + namespaceEndIndex = string.find (qName, ':') + if namespaceEndIndex != -1: + prefix = qName[:namespaceEndIndex] + localName = qName[namespaceEndIndex+1:] + else: + prefix = None + localName = qName + return prefix, localName + + +def toClarkQName (tupleOrLocalName): + """converts a tuple (namespace, localName) into clark notation {namespace}localName + qNames without namespace remain unchanged + + Input parameter: + 'tupleOrLocalName': tuple '(namespace, localName)' to be converted + Returns a string {namespace}localName + """ + if isinstance(tupleOrLocalName, TupleType): + if tupleOrLocalName[0] != EMPTY_NAMESPACE: + return "{%s}%s" %(tupleOrLocalName[0], tupleOrLocalName[1]) + else: + return tupleOrLocalName[1] + else: + return tupleOrLocalName + + +def splitClarkQName (qName): + """converts clark notation {namespace}localName into a tuple (namespace, localName) + + Input parameter: + 'qName': {namespace}localName to be converted + Returns prefix and localName as separate strings + """ + namespaceEndIndex = string.find (qName, '}') + if namespaceEndIndex != -1: + prefix = qName[1:namespaceEndIndex] + localName = qName[namespaceEndIndex+1:] + else: + prefix = None + localName = qName + return prefix, localName + + +################################################################## +# XML serialization of text +# the following functions assume an ascii-compatible encoding +# (or "utf-16") + +_escape = re.compile(eval(r'u"[&<>\"\u0080-\uffff]+"')) + +_escapeDict = { + "&": "&", + "<": "<", + ">": ">", + '"': """, +} + + +def _raiseSerializationError(text): + raise TypeError("cannot serialize %r (type %s)" % (text, type(text).__name__)) + + +def _encode(text, encoding): + try: + return text.encode(encoding) + except AttributeError: + return text # assume the string uses the right encoding + + +def _encodeEntity(text, pattern=_escape): + # map reserved and non-ascii characters to numerical entities + def escapeEntities(m, map=_escapeDict): + out = [] + append = out.append + for char in m.group(): + text = map.get(char) + if text is None: + text = "&#%d;" % ord(char) + append(text) + return string.join(out, "") + try: + return _encode(pattern.sub(escapeEntities, text), "ascii") + except TypeError: + _raise_serialization_error(text) + + +def escapeCdata(text, encoding=None, replace=string.replace): + # escape character data + try: + if encoding: + try: + text = _encode(text, encoding) + except UnicodeError: + return _encodeEntity(text) + text = replace(text, "&", "&") + text = replace(text, "<", "<") + text = replace(text, ">", ">") + return text + except (TypeError, AttributeError): + _raiseSerializationError(text) + + +def escapeAttribute(text, encoding=None, replace=string.replace): + # escape attribute value + try: + if encoding: + try: + text = _encode(text, encoding) + except UnicodeError: + return _encodeEntity(text) + text = replace(text, "&", "&") + text = replace(text, "'", "'") # FIXME: overkill + text = replace(text, "\"", """) + text = replace(text, "<", "<") + text = replace(text, ">", ">") + return text + except (TypeError, AttributeError): + _raiseSerializationError(text) + + +###################################################################### +# CLASSES +###################################################################### + +###################################################################### +# class containing a tuple of namespace prefix and localName +# +class QNameTuple(tuple): + def __str__(self): + if self[0] != EMPTY_PREFIX: + return "%s:%s" %(self[0],self[1]) + else: + return self[1] + + +def QNameTupleFactory(initValue): + if isinstance(initValue, StringTypes): + separatorIndex = string.find (initValue, ':') + if separatorIndex != -1: + initValue = (initValue[:separatorIndex], initValue[separatorIndex+1:]) + else: + initValue = (EMPTY_PREFIX, initValue) + return QNameTuple(initValue) + + +###################################################################### +# class containing a tuple of namespace and localName +# +class NsNameTuple(tuple): + def __str__(self): + if self[0] != EMPTY_NAMESPACE: + return "{%s}%s" %(self[0],self[1]) + elif self[1] != None: + return self[1] + else: + return "None" + + +def NsNameTupleFactory(initValue): + if isinstance(initValue, StringTypes): + initValue = splitClarkQName(initValue) + elif initValue == None: + initValue = (EMPTY_NAMESPACE, initValue) + return NsNameTuple(initValue) + + diff --git a/pymavlink/generator/lib/genxmlif/xmliftest.py b/pymavlink/generator/lib/genxmlif/xmliftest.py new file mode 100644 index 0000000..7c26f78 --- /dev/null +++ b/pymavlink/generator/lib/genxmlif/xmliftest.py @@ -0,0 +1,14 @@ +from .. import genxmlif +from ..genxmlif.xmlifODict import odict + +xmlIf = genxmlif.chooseXmlIf(genxmlif.XMLIF_ELEMENTTREE) +xmlTree = xmlIf.createXmlTree(None, "testTree", {"rootAttr1":"RootAttr1"}) +xmlRootNode = xmlTree.getRootNode() +myDict = odict( (("childTag1","123"), ("childTag2","123")) ) +xmlRootNode.appendChild("childTag", myDict) +xmlRootNode.appendChild("childTag", {"childTag1":"123456", "childTag2":"123456"}) +xmlRootNode.appendChild("childTag", {"childTag1":"123456789", "childTag3":"1234", "childTag2":"123456789"}) +xmlRootNode.appendChild("childTag", {"childTag1":"1", "childTag2":"1"}) +print xmlTree.printTree(prettyPrint=1) +print xmlTree +print xmlTree.getRootNode() diff --git a/pymavlink/generator/lib/minixsv/README.txt b/pymavlink/generator/lib/minixsv/README.txt new file mode 100644 index 0000000..c887e7d --- /dev/null +++ b/pymavlink/generator/lib/minixsv/README.txt @@ -0,0 +1,178 @@ +Release Notes for minixsv, Release 0.9.0 + +minixsv is a XML schema validator written in "pure" Python +(minixsv requires at least Python 2.4) + +Currently a subset of the XML schema standard is supported +(list of limitations/restrictions see below). + +minixsv is based on genxmlif, a generic XML interface class, +which currently supports minidom, elementtree or 4DOM/pyXML as XML parser +Other parsers can be adapted by implementing an appropriate derived interface class + +Using the 4DOM interface is rather slow. +For best performance the elementtree parser should be used! + +After successful validation minixsv provides the input XML tree with the following changes: +- Whitespaces inside strings are automatically normalized/collapsed as specified + in the XML schema file +- Default/Fixed attributes are automatically inserted if not specified in the input file +- The "post validation" XML tree can be accessed using genxmlif or the contained + original interface (minidom, elementtree or 4DOM/pyXML). + +-------------------------------------------------------------------- + The minixsv XML schema validator is + + Copyright (c) 2004-2008 by Roland Leuthe + + By obtaining, using, and/or copying this software and/or its + associated documentation, you agree that you have read, understood, + and will comply with the following terms and conditions: + + Permission to use, copy, modify, and distribute this software and + its associated documentation for any purpose and without fee is + hereby granted, provided that the above copyright notice appears in + all copies, and that both that copyright notice and this permission + notice appear in supporting documentation, and that the name of + the author not be used in advertising or publicity + pertaining to distribution of the software without specific, written + prior permission. + + THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD + TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- + ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR + BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY + DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, + WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS + ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE + OF THIS SOFTWARE. +--------------------------------------------------------------------- + + +Limitations/restrictions of the current release: + +- no checks if derived type and base type match +- no check of attributes "final", "finalDefault" +- no support of substitution groups +- no support of abstract elements and types +- restrictions regarding for pattern matching: + * subtraction of character sets not supported, e.g. regex = "[\w-[ab]]" + * characters sets with \I, \C, \P{...} not supported, e.g. regex = "[\S\I\?a-c\?]" + (character sets with \i, \c, \p{...} are supported!) + +Note: This constraint list may not be complete!! + + +--------------------------------------------------------------------- + +Contents +======== + +README.txt +__init__.py +minixsv +minixsvWrapper.py +pyxsval.py +xsvalBase.py +xsvalErrorHandler.py +xsvalSchema.py +xsvalSimpleTypes.py +xsvalUtils.py +xsvalXmlIf.py +datatypes.xsd +XInclude.xsd +xml.xsd +XMLSchema.xsd +XMLSchema-instance.xsd + +--------------------------------------------------------------------- + +HISTORY: +======= + +Changes for Release 0.9.0 +========================= + +- Caution, Interface changed! + * In case of parser and XInclude errors now a GenXmlIfError exception is raised! + * New optional parameter 'useCaching=1' and 'processXInclude=1' to XsValidator class added + +- check of facets of derived primitive types added +- unicode support added (except wide unicode characters) +- major improvements for pattern matching (but there are still some restrictions, refer above) +- limited support of XInclude added (no support of fallback tag) +- performance optimizations (caching introduced) +- several bugs fixed (new W3C test suite (2006-11-06) passed for supported features) + 3943 of 3953 nisttest testgroups passed + 8645 of 9745 mstest testgroups passed + 559 of 679 suntest testgroups passed + (most not passed test groups correspond to the limitations listed above) + + +Changes for Release 0.8 +======================= + +- Caution, Interface changed! + When calling the validator (e.g. using parseAndValidate or parseAndValidateString) + the input parameter xsdFile/xsdText is only used if no schema file is specified in the XML input file/string, + i.e. the schema specification in the XML input file/string has now priority!! + +- uniqueness of attribute/attributeGroup/type IDs now checked +- problems with different target namespaces fixed +- "redefine" element now supported +- performance optimization due to optimized genxmlif (when elementtree parser is used) +- several bugs fixed (W3C test suite passed for supported features) + 3953 of 3953 nisttest testgroups passed + 4260 of 4529 msxsdtest testgroups passed + 31 of 40 suntest testgroups passed + (most not passed test groups correspond to the limitations listed above) + + +Changes for Release 0.7 +======================= + +- now all primitive data types are supported +- check if no element content exists when xsi:nil = "true" is specified +- support of "processContents" attribute +- correct uniqueness checking of identity constraints (unique/key/keyref) +- many bugs fixed (W3C test suite passed for supported features) + 3953 of 3953 nisttest testgroups passed + 3996 of 4529 msxsdtest testgroups passed + 27 of 40 suntest testgroups passed + (most not passed test groups correspond to the limitations listed above) + + +Changes for Release 0.5 +======================= + +- generic XML interface extracted into a separate python package +- namespace support added +- 4DOM support added +- support of attributes "elementFormDefault", "attributeFormDefault", "form" added +- support of "import" element added +- handling of "schemaLocation" and "noNamespaceSchemaLocation" corrected +- support of derivation of complex types from simple types (extension) added +- support of mixed content (child nodes and text nodes) added +- new access function to add user defined XML interface class +- new access function to add user defined validation function for unsupported predefined types +- several bugs fixed + + +Changes for Release 0.3 +======================= + +- API re-structured +- XML text processing added +- several bugs fixed +- internal re-structuring + + +Changes for Release 0.2 +======================= + +- Error/warning outputs contain now also filename and linenumber +- Basic URI support for include directive added +- XML interface classes completely re-designed +- several bugs fixed + + diff --git a/pymavlink/generator/lib/minixsv/XInclude.xsd b/pymavlink/generator/lib/minixsv/XInclude.xsd new file mode 100644 index 0000000..f0a4c98 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/XInclude.xsd @@ -0,0 +1,46 @@ + + + + + Not normative, but may be useful. + See the REC http://www.w3.org/TR/XInclude for definitive + information about this namespace. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/pymavlink/generator/lib/minixsv/XMLSchema-instance.xsd b/pymavlink/generator/lib/minixsv/XMLSchema-instance.xsd new file mode 100644 index 0000000..517af42 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/XMLSchema-instance.xsd @@ -0,0 +1,28 @@ + + + + + +

XML Schema instance namespace

+

See the XML Schema + Recommendation for an introduction

+ + +
+ $Date: 2001/03/16 20:25:57 $
+ $Id: XMLSchema-instance.xsd,v 1.4 2001/03/16 20:25:57 ht Exp $ +
+
+ +

This schema should never be used as such: + the XML + Schema Recommendation forbids the declaration of + attributes in this namespace

+
+
+ + + + + +
\ No newline at end of file diff --git a/pymavlink/generator/lib/minixsv/XMLSchema.xsd b/pymavlink/generator/lib/minixsv/XMLSchema.xsd new file mode 100644 index 0000000..7a50f75 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/XMLSchema.xsd @@ -0,0 +1,1195 @@ + + + + + + + + + + + + The schema corresponding to this document is normative, + with respect to the syntactic constraints it expresses in the + XML Schema language. The documentation (within <documentation> elements) + below, is not normative, but rather highlights important aspects of + the W3C Recommendation of which this is a part + + + + + The simpleType element and all of its members are defined + in datatypes.xsd + + + + + + + + Get access to the xml: attribute groups for xml:lang + as declared on 'schema' and 'documentation' below + + + + + + + + This type is extended by almost all schema types + to allow attributes from other namespaces to be + added to user schemas. + + + + + + + + + + + + + This type is extended by all types which allow annotation + other than <schema> itself + + + + + + + + + + + + + + + + This group is for the + elements which occur freely at the top level of schemas. + All of their types are based on the "annotated" type by extension. + + + + + + + + + + + + + + This group is for the + elements which can self-redefine (see <redefine> below). + + + + + + + + + + + + + + A utility type, not for public use + + + + + + + + + + + + A utility type, not for public use + + + + + + + + + + + + A utility type, not for public use + + + #all or (possibly empty) subset of {extension, restriction} + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + for maxOccurs + + + + + + + + + + + + for all particles + + + + + + + for element, group and attributeGroup, + which both define and reference + + + + + + + + 'complexType' uses this + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + This branch is short for + <complexContent> + <restriction base="xs:anyType"> + ... + </restriction> + </complexContent> + + + + + + + + + + + + + + + + Will be restricted to required or forbidden + + + + + + + Not allowed if simpleContent child is chosen. + May be overriden by setting on complexContent child. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Overrides any setting on complexType parent. + + + + + + + + + + + + + + + + + + + + + + + + + + No typeDefParticle group reference + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + A utility type, not for public use + + #all or (possibly empty) subset of {substitution, extension, + restriction} + + + + + + + + + + + + + + + + + + + + + + + + + The element element can be used either + at the top level to define an element-type binding globally, + or within a content model to either reference a globally-defined + element or type or declare an element-type binding locally. + The ref form is not allowed at the top level. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + group type for explicit groups, named top-level groups and + group references + + + + + + + + + + + + + + + + + + + + + + + + + + + + Should derive this from realGroup, but too complicated + for now + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + group type for the three kinds of group + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + restricted max/min + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Only elements allowed inside + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + simple type for the value of the 'namespace' attr of + 'any' and 'anyAttribute' + + + + Value is + ##any - - any non-conflicting WFXML/attribute at all + + ##other - - any non-conflicting WFXML/attribute from + namespace other than targetNS + + ##local - - any unqualified non-conflicting WFXML/attribute + + one or - - any non-conflicting WFXML/attribute from + more URI the listed namespaces + references + (space separated) + + ##targetNamespace or ##local may appear in the above list, to + refer to the targetNamespace of the enclosing + schema or an absent targetNamespace respectively + + + + + + A utility type, not for public use + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + A subset of XPath expressions for use +in selectors + A utility type, not for public +use + + + + The following pattern is intended to allow XPath + expressions per the following EBNF: + Selector ::= Path ( '|' Path )* + Path ::= ('.//')? Step ( '/' Step )* + Step ::= '.' | NameTest + NameTest ::= QName | '*' | NCName ':' '*' + child:: is also allowed + + + + + + + + + + + + + + + + + + + + + + + A subset of XPath expressions for use +in fields + A utility type, not for public +use + + + + The following pattern is intended to allow XPath + expressions per the same EBNF as for selector, + with the following change: + Path ::= ('.//')? ( Step '/' )* ( Step | '@' NameTest ) + + + + + + + + + + + + + + + + + + + + + + + + + + + The three kinds of identity constraints, all with + type of or derived from 'keybase'. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + A utility type, not for public use + + A public identifier, per ISO 8879 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + notations for use within XML Schema schemas + + + + + + + + + Not the real urType, but as close an approximation as we can + get in the XML representation + + + + + + + + + + diff --git a/pymavlink/generator/lib/minixsv/__init__.py b/pymavlink/generator/lib/minixsv/__init__.py new file mode 100644 index 0000000..aca1a89 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/__init__.py @@ -0,0 +1,75 @@ +# +# minixsv, Release 0.9.0 +# file: __init__.py +# +# minixsv package file +# +# history: +# 2004-10-26 rl created +# +# Copyright (c) 2004-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The minixsv XML schema validator is +# +# Copyright (c) 2004-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + + +###################################################################### +# PUBLIC DEFINITIONS +###################################################################### + + +# supported XML interfaces + +XMLIF_MINIDOM = "XMLIF_MINIDOM" +XMLIF_4DOM = "XMLIF_4DOM" +XMLIF_ELEMENTTREE = "XMLIF_ELEMENTTREE" + + + +# namespace definitions + +EMPTY_PREFIX = None + +EMPTY_NAMESPACE = None +XML_NAMESPACE = "http://www.w3.org/XML/1998/namespace" +XMLNS_NAMESPACE = "http://www.w3.org/2000/xmlns/" +XSD_NAMESPACE = "http://www.w3.org/2001/XMLSchema" +XSI_NAMESPACE = "http://www.w3.org/2001/XMLSchema-instance" + + +# definition of minixsv path + +import os +MINIXSV_DIR = os.path.dirname(__file__) + + +# error handling definitions + +from xsvalErrorHandler import IGNORE_WARNINGS, PRINT_WARNINGS, STOP_ON_WARNINGS +from xsvalErrorHandler import XsvalError + diff --git a/pymavlink/generator/lib/minixsv/datatypes.xsd b/pymavlink/generator/lib/minixsv/datatypes.xsd new file mode 100644 index 0000000..09c1dc1 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/datatypes.xsd @@ -0,0 +1,1222 @@ + + + + + + + The schema corresponding to this document is normative, + with respect to the syntactic constraints it expresses in the + XML Schema language. The documentation (within <documentation> + elements) below, is not normative, but rather highlights important + aspects of the W3C Recommendation of which this is a part + + + + + + First the built-in primitive datatypes. These definitions are for + information only, the real built-in definitions are magic. Note in + particular that there is no type named 'anySimpleType'. The + primitives should really be derived from no type at all, and + anySimpleType should be derived as a union of all the primitives. + + + + For each built-in datatype in this schema (both primitive and + derived) can be uniquely addressed via a URI constructed + as follows: + 1) the base URI is the URI of the XML Schema namespace + 2) the fragment identifier is the name of the datatype + + For example, to address the int datatype, the URI is: + + http://www.w3.org/2001/XMLSchema#int + + Additionally, each facet definition element can be uniquely + addressed via a URI constructed as follows: + 1) the base URI is the URI of the XML Schema namespace + 2) the fragment identifier is the name of the facet + + For example, to address the maxInclusive facet, the URI is: + + http://www.w3.org/2001/XMLSchema#maxInclusive + + Additionally, each facet usage in a built-in datatype definition + can be uniquely addressed via a URI constructed as follows: + 1) the base URI is the URI of the XML Schema namespace + 2) the fragment identifier is the name of the datatype, followed + by a period (".") followed by the name of the facet + + For example, to address the usage of the maxInclusive facet in + the definition of int, the URI is: + + http://www.w3.org/2001/XMLSchema#int.maxInclusive + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + NOTATION cannot be used directly in a schema; rather a type + must be derived from it by specifying at least one enumeration + facet whose value is the name of a NOTATION declared in the + schema. + + + + + + + + + + Now the derived primitive types + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + pattern specifies the content of section 2.12 of XML 1.0e2 + and RFC 1766 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + pattern matches production 7 from the XML spec + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + pattern matches production 5 from the XML spec + + + + + + + + + + + + + + + pattern matches production 4 from the Namespaces in XML spec + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + A utility type, not for public use + + + + + + + + + + + + + + + + + + + + + + #all or (possibly empty) subset of {restriction, union, list} + + + A utility type, not for public use + + + + + + + + + + + + + + + + + + + + + + + + + + Can be restricted to required or forbidden + + + + + + + + + + + + + + + + + + Required at the top level + + + + + + + + + + + + + + + + + + Forbidden when nested + + + + + + + + + + + + + + + + + + We should use a substitution group for facets, but + that's ruled out because it would allow users to + add their own, which we're not ready for yet. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + base attribute and simpleType child are mutually + exclusive, but one or other is required + + + + + + + + + + + + + + + + itemType attribute and simpleType child are mutually + exclusive, but one or other is required + + + + + + + + + + + + + + + + + + memberTypes attribute must be non-empty or there must be + at least one simpleType child + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/pymavlink/generator/lib/minixsv/minixsv b/pymavlink/generator/lib/minixsv/minixsv new file mode 100644 index 0000000..3759755 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/minixsv @@ -0,0 +1,3 @@ +#!/usr/local/bin/python +from minixsv import minixsvWrapper +minixsvWrapper.main() \ No newline at end of file diff --git a/pymavlink/generator/lib/minixsv/minixsvWrapper.py b/pymavlink/generator/lib/minixsv/minixsvWrapper.py new file mode 100644 index 0000000..d4a3b1d --- /dev/null +++ b/pymavlink/generator/lib/minixsv/minixsvWrapper.py @@ -0,0 +1,76 @@ +#!/usr/local/bin/python + +import sys +import getopt +from ..genxmlif import GenXmlIfError +from xsvalErrorHandler import ErrorHandler, XsvalError +from ..minixsv import * +from pyxsval import parseAndValidate + + +########################################## +# minixsv Wrapper for calling minixsv from command line + +validSyntaxText = '''\ +minixsv XML Schema Validator +Syntax: minixsv [-h] [-?] [-p Parser] [-s XSD-Filename] XML-Filename + +Options: +-h, -?: Display this help text +-p Parser: XML Parser to be used + (XMLIF_MINIDOM, XMLIF_ELEMENTTREE, XMLIF_4DOM + default: XMLIF_ELEMENTTREE) +-s XSD-FileName: specify the schema file for validation + (if not specified in XML-File) +''' + +def checkShellInputParameter(): + """check shell input parameters.""" + xmlInputFilename = None + xsdFilename = None + xmlParser = "XMLIF_ELEMENTTREE" + try: + (options, arguments) = getopt.getopt(sys.argv[1:], '?hp:s:') + + if ('-?','') in options or ('-h','') in options: + print validSyntaxText + sys.exit(-1) + else: + if len (arguments) == 1: + xmlInputFilename = arguments[0] + for o, a in options: + if o == "-s": + xsdFilename = a + if o == "-p": + if a in (XMLIF_MINIDOM, XMLIF_ELEMENTTREE, XMLIF_4DOM): + xmlParser = a + else: + print 'Invalid XML parser %s!' %(a) + sys.exit(-1) + else: + print 'minixsv needs one argument (XML input file)!' + sys.exit(-1) + + except getopt.GetoptError, errstr: + print errstr + sys.exit(-1) + return xmlInputFilename, xsdFilename, xmlParser + + +def main(): + xmlInputFilename, xsdFileName, xmlParser = checkShellInputParameter() + try: + parseAndValidate (xmlInputFilename, xsdFile=xsdFileName, xmlIfClass=xmlParser) + except IOError, errstr: + print errstr + sys.exit(-1) + except GenXmlIfError, errstr: + print errstr + sys.exit(-1) + except XsvalError, errstr: + print errstr + sys.exit(-1) + +if __name__ == "__main__": + main() + diff --git a/pymavlink/generator/lib/minixsv/pyxsval.py b/pymavlink/generator/lib/minixsv/pyxsval.py new file mode 100644 index 0000000..44c264b --- /dev/null +++ b/pymavlink/generator/lib/minixsv/pyxsval.py @@ -0,0 +1,373 @@ +# +# minixsv, Release 0.9.0 +# file: pyxsval.py +# +# API for XML schema validator +# +# history: +# 2004-09-09 rl created +# 2004-09-29 rl adapted to re-designed XML interface classes, +# ErrorHandler separated, URL processing added, some bugs fixed +# 2004-10-07 rl Validator classes extracted into separate files +# 2004-10-12 rl API re-worked, XML text processing added +# 2007-05-15 rl Handling of several schema files added, +# schema references in the input file have now priority (always used if available!) +# 2008-08-01 rl New optional parameter 'useCaching=1' and 'processXInclude=1' to XsValidator class added +# +# Copyright (c) 2004-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The minixsv XML schema validator is +# +# Copyright (c) 2004-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +__all__ = [ + # public symbols + "addUserSpecXmlIfClass", + "parseAndValidate", + "parseAndValidateString", + "parseAndValidateXmlInput", + "parseAndValidateXmlInputString", + "parseAndValidateXmlSchema", + "parseAndValidateXmlSchemaString", + "XsValidator", + ] + + +import string +from .. import genxmlif +from ..minixsv import * +from xsvalErrorHandler import ErrorHandler +from xsvalXmlIf import XsvXmlElementWrapper +from xsvalBase import XsValBase +from xsvalSchema import XsValSchema + + +__author__ = "Roland Leuthe " +__date__ = "08. August 2008" +__version__ = "0.9.0" + + +_XS_VAL_DEFAULT_ERROR_LIMIT = 20 + +rulesTreeWrapper = None # XML tree cache for "XMLSchema.xsd" + + +######################################## +# retrieve version of minixsv +# +def getVersion (): + return __version__ + + +######################################## +# access function for adding a user specific XML interface class +# +def addUserSpecXmlIfClass (xmlIfKey, factory): + if not _xmlIfDict.has_key(xmlIfKey): + _xmlIfDict[xmlIfKey] = factory + else: + raise KeyError, "xmlIfKey %s already implemented!" %(xmlIfKey) + + +######################################## +# convenience function for validating +# 1. XML schema file +# 2. XML input file +# If xsdFile is specified, it will ONLY be used for validation if no schema file +# is specified in the input file +# If xsdFile=None, the schemaLocation attribute is expected in the root tag of the XML input file +# +def parseAndValidate (inputFile, xsdFile=None, **kw): + return parseAndValidateXmlInput (inputFile, xsdFile, 1, **kw) + + +######################################## +# convenience function for validating +# 1. text string containing the XML schema +# 2. text string containing the XML input +# If xsdText is given, it will ONLY be used for validation if no schema file +# is specified in the input text +# If xsdText=None, the schemaLocation attribute is expected in the root tag of the XML input +# +def parseAndValidateString (inputText, xsdText=None, **kw): + return parseAndValidateXmlInputString (inputText, xsdText, 1, **kw) + + +######################################## +# factory for validating +# 1. XML schema file (only if validateSchema=1) +# 2. XML input file +# If xsdFile is specified, it will ONLY be used for validation if no schema file +# is specified in the input file +# If xsdFile=None, the schemaLocation attribute is expected in the root tag of the XML input file +# +def parseAndValidateXmlInput (inputFile, xsdFile=None, validateSchema=0, **kw): + xsValidator = XsValidator (**kw) + # parse XML input file + inputTreeWrapper = xsValidator.parse (inputFile) + # validate XML input file + return xsValidator.validateXmlInput (inputFile, inputTreeWrapper, xsdFile, validateSchema) + + +######################################## +# factory for validating +# 1. text string containing the XML schema (only if validateSchema=1) +# 2. text string containing the XML input +# If xsdText is given, it will ONLY be used for validation if no schema file +# is specified in the input text +# If xsdText=None, the schemaLocation attribute is expected in the root tag of the XML input +# +def parseAndValidateXmlInputString (inputText, xsdText=None, baseUrl="", validateSchema=0, **kw): + xsValidator = XsValidator (**kw) + # parse XML input text string + inputTreeWrapper = xsValidator.parseString (inputText, baseUrl) + # validate XML input text string + return xsValidator.validateXmlInputString (inputTreeWrapper, xsdText, validateSchema) + + +######################################## +# factory for validating only given XML schema file +# +def parseAndValidateXmlSchema (xsdFile, **kw): + xsValidator = XsValidator (**kw) + # parse XML schema file + xsdTreeWrapper = xsValidator.parse (xsdFile) + # validate XML schema file + return xsValidator.validateXmlSchema (xsdFile, xsdTreeWrapper) + + +######################################## +# factory for validating only given XML schema file +# +def parseAndValidateXmlSchemaString (xsdText, **kw): + xsValidator = XsValidator (**kw) + # parse XML schema + xsdTreeWrapper = xsValidator.parseString (xsdText) + # validate XML schema + return xsValidator.validateXmlSchema ("", xsdTreeWrapper) + + +######################################## +# XML schema validator class +# +class XsValidator: + def __init__(self, xmlIfClass=XMLIF_MINIDOM, + elementWrapperClass=XsvXmlElementWrapper, + warningProc=IGNORE_WARNINGS, errorLimit=_XS_VAL_DEFAULT_ERROR_LIMIT, + verbose=0, useCaching=1, processXInclude=1): + + self.warningProc = warningProc + self.errorLimit = errorLimit + self.verbose = verbose + + # select XML interface class + self.xmlIf = _xmlIfDict[xmlIfClass](verbose, useCaching, processXInclude) + self.xmlIf.setElementWrapperClass (elementWrapperClass) + + # create error handler + self.errorHandler = ErrorHandler (errorLimit, warningProc, verbose) + + self.schemaDependancyList = [] + + + ######################################## + # retrieve current version + # + def getVersion (self): + return __version__ + + + ######################################## + # parse XML file + # 'file' may be a filepath or an URI + # + def parse (self, file, baseUrl="", ownerDoc=None): + self._verbosePrint ("Parsing %s..." %(file)) + return self.xmlIf.parse(file, baseUrl, ownerDoc) + + + ######################################## + # parse text string containing XML + # + def parseString (self, text, baseUrl=""): + self._verbosePrint ("Parsing XML text string...") + return self.xmlIf.parseString(text, baseUrl) + + + ######################################## + # validate XML input + # + def validateXmlInput (self, xmlInputFile, inputTreeWrapper, xsdFile=None, validateSchema=0): + # if the input file contains schema references => use these + xsdTreeWrapperList = self._readReferencedXsdFiles(inputTreeWrapper, validateSchema) + if xsdTreeWrapperList == []: + # if the input file doesn't contain schema references => use given xsdFile + if xsdFile != None: + xsdTreeWrapper = self.parse (xsdFile) + xsdTreeWrapperList.append(xsdTreeWrapper) + # validate XML schema file if requested + if validateSchema: + self.validateXmlSchema (xsdFile, xsdTreeWrapper) + else: + self.errorHandler.raiseError ("No schema file specified!") + + self._validateXmlInput (xmlInputFile, inputTreeWrapper, xsdTreeWrapperList) + for xsdTreeWrapper in xsdTreeWrapperList: + xsdTreeWrapper.unlink() + return inputTreeWrapper + + ######################################## + # validate XML input + # + def validateXmlInputString (self, inputTreeWrapper, xsdText=None, validateSchema=0): + # if the input file contains schema references => use these + xsdTreeWrapperList = self._readReferencedXsdFiles(inputTreeWrapper, validateSchema) + if xsdTreeWrapperList == []: + # if the input file doesn't contain schema references => use given xsdText + if xsdText != None: + xsdFile = "schema text" + xsdTreeWrapper = self.parseString (xsdText) + xsdTreeWrapperList.append(xsdTreeWrapper) + # validate XML schema file if requested + if validateSchema: + self.validateXmlSchema (xsdFile, xsdTreeWrapper) + else: + self.errorHandler.raiseError ("No schema specified!") + + self._validateXmlInput ("input text", inputTreeWrapper, xsdTreeWrapperList) + for xsdTreeWrapper in xsdTreeWrapperList: + xsdTreeWrapper.unlink() + return inputTreeWrapper + + + ######################################## + # validate XML schema separately + # + def validateXmlSchema (self, xsdFile, xsdTreeWrapper): + # parse minixsv internal schema + global rulesTreeWrapper + if rulesTreeWrapper == None: + rulesTreeWrapper = self.parse(os.path.join (MINIXSV_DIR, "XMLSchema.xsd")) + + self._verbosePrint ("Validating %s..." %(xsdFile)) + xsvGivenXsdFile = XsValSchema (self.xmlIf, self.errorHandler, self.verbose) + xsvGivenXsdFile.validate(xsdTreeWrapper, [rulesTreeWrapper,]) + self.schemaDependancyList.append (xsdFile) + self.schemaDependancyList.extend (xsvGivenXsdFile.xsdIncludeDict.keys()) + xsvGivenXsdFile.unlink() + self.errorHandler.flushOutput() + return xsdTreeWrapper + + + ######################################## + # validate XML input tree and xsd tree if requested + # + def _validateXmlInput (self, xmlInputFile, inputTreeWrapper, xsdTreeWrapperList): + self._verbosePrint ("Validating %s..." %(xmlInputFile)) + xsvInputFile = XsValBase (self.xmlIf, self.errorHandler, self.verbose) + xsvInputFile.validate(inputTreeWrapper, xsdTreeWrapperList) + xsvInputFile.unlink() + self.errorHandler.flushOutput() + + + ######################################## + # retrieve XML schema location from XML input tree + # + def _readReferencedXsdFiles (self, inputTreeWrapper, validateSchema): + xsdTreeWrapperList = [] + # a schemaLocation attribute is expected in the root tag of the XML input file + xsdFileList = self._retrieveReferencedXsdFiles (inputTreeWrapper) + for namespace, xsdFile in xsdFileList: + try: + xsdTreeWrapper = self.parse (xsdFile, inputTreeWrapper.getRootNode().getAbsUrl()) + except IOError, e: + if e.errno == 2: # catch IOError: No such file or directory + self.errorHandler.raiseError ("XML schema file %s not found!" %(xsdFile), inputTreeWrapper.getRootNode()) + else: + raise IOError(e.errno, e.strerror, e.filename) + + xsdTreeWrapperList.append(xsdTreeWrapper) + # validate XML schema file if requested + if validateSchema: + self.validateXmlSchema (xsdFile, xsdTreeWrapper) + + if namespace != xsdTreeWrapper.getRootNode().getAttributeOrDefault("targetNamespace", None): + self.errorHandler.raiseError ("Namespace of 'schemaLocation' attribute doesn't match target namespace of %s!" %(xsdFile), inputTreeWrapper.getRootNode()) + + return xsdTreeWrapperList + + + ######################################## + # retrieve XML schema location from XML input tree + # + def _retrieveReferencedXsdFiles (self, inputTreeWrapper): + # a schemaLocation attribute is expected in the root tag of the XML input file + inputRootNode = inputTreeWrapper.getRootNode() + xsdFileList = [] + + if inputRootNode.hasAttribute((XSI_NAMESPACE, "schemaLocation")): + attributeValue = inputRootNode.getAttribute((XSI_NAMESPACE, "schemaLocation")) + attrValList = string.split(attributeValue) + if len(attrValList) % 2 == 0: + for i in range(0, len(attrValList), 2): + xsdFileList.append((attrValList[i], attrValList[i+1])) + else: + self.errorHandler.raiseError ("'schemaLocation' attribute must have even number of URIs (pairs of namespace and xsdFile)!") + + if inputRootNode.hasAttribute((XSI_NAMESPACE, "noNamespaceSchemaLocation")): + attributeValue = inputRootNode.getAttribute((XSI_NAMESPACE, "noNamespaceSchemaLocation")) + attrValList = string.split(attributeValue) + for attrVal in attrValList: + xsdFileList.append ((None, attrVal)) + + return xsdFileList + + ######################################## + # print if verbose flag is set + # + def _verbosePrint (self, text): + if self.verbose: + print text + + +######################################## +# factory functions for enabling the selected XML interface class +# +def _interfaceFactoryMinidom (verbose, useCaching, processXInclude): + return genxmlif.chooseXmlIf(genxmlif.XMLIF_MINIDOM, verbose, useCaching, processXInclude) + +def _interfaceFactory4Dom (verbose, useCaching, processXInclude): + return genxmlif.chooseXmlIf(genxmlif.XMLIF_4DOM, verbose, useCaching, processXInclude) + +def _interfaceFactoryElementTree (verbose, useCaching, processXInclude): + return genxmlif.chooseXmlIf(genxmlif.XMLIF_ELEMENTTREE, verbose, useCaching, processXInclude) + + +_xmlIfDict = {XMLIF_MINIDOM :_interfaceFactoryMinidom, + XMLIF_4DOM :_interfaceFactory4Dom, + XMLIF_ELEMENTTREE:_interfaceFactoryElementTree} + diff --git a/pymavlink/generator/lib/minixsv/xml.xsd b/pymavlink/generator/lib/minixsv/xml.xsd new file mode 100644 index 0000000..cb81606 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/xml.xsd @@ -0,0 +1,134 @@ + + + + + + See http://www.w3.org/XML/1998/namespace.html and + http://www.w3.org/TR/REC-xml for information about this namespace. + + This schema document describes the XML namespace, in a form + suitable for import by other schema documents. + + Note that local names in this namespace are intended to be defined + only by the World Wide Web Consortium or its subgroups. The + following names are currently defined in this namespace and should + not be used with conflicting semantics by any Working Group, + specification, or document instance: + + base (as an attribute name): denotes an attribute whose value + provides a URI to be used as the base for interpreting any + relative URIs in the scope of the element on which it + appears; its value is inherited. This name is reserved + by virtue of its definition in the XML Base specification. + + id (as an attribute name): denotes an attribute whose value + should be interpreted as if declared to be of type ID. + The xml:id specification is not yet a W3C Recommendation, + but this attribute is included here to facilitate experimentation + with the mechanisms it proposes. Note that it is _not_ included + in the specialAttrs attribute group. + + lang (as an attribute name): denotes an attribute whose value + is a language code for the natural language of the content of + any element; its value is inherited. This name is reserved + by virtue of its definition in the XML specification. + + space (as an attribute name): denotes an attribute whose + value is a keyword indicating what whitespace processing + discipline is intended for the content of the element; its + value is inherited. This name is reserved by virtue of its + definition in the XML specification. + + Father (in any context at all): denotes Jon Bosak, the chair of + the original XML Working Group. This name is reserved by + the following decision of the W3C XML Plenary and + XML Coordination groups: + + In appreciation for his vision, leadership and dedication + the W3C XML Plenary on this 10th day of February, 2000 + reserves for Jon Bosak in perpetuity the XML name + xml:Father + + + + + This schema defines attributes and an attribute group + suitable for use by + schemas wishing to allow xml:base, xml:lang or xml:space attributes + on elements they define. + + To enable this, such a schema must import this schema + for the XML namespace, e.g. as follows: + <schema . . .> + . . . + <import namespace="http://www.w3.org/XML/1998/namespace" + schemaLocation="http://www.w3.org/2001/03/xml.xsd"/> + + Subsequently, qualified reference to any of the attributes + or the group defined below will have the desired effect, e.g. + + <type . . .> + . . . + <attributeGroup ref="xml:specialAttrs"/> + + will define a type which will schema-validate an instance + element with any of those attributes + + + + In keeping with the XML Schema WG's standard versioning + policy, this schema document will persist at + http://www.w3.org/2004/10/xml.xsd. + At the date of issue it can also be found at + http://www.w3.org/2001/xml.xsd. + The schema document at that URI may however change in the future, + in order to remain compatible with the latest version of XML Schema + itself. In other words, if the XML Schema namespace changes, the version + of this document at + http://www.w3.org/2001/xml.xsd will change + accordingly; the version at + http://www.w3.org/2004/10/xml.xsd will not change. + + + + + + Attempting to install the relevant ISO 2- and 3-letter + codes as the enumerated possible values is probably never + going to be a realistic possibility. See + RFC 3066 at http://www.ietf.org/rfc/rfc3066.txt and the IANA registry + at http://www.iana.org/assignments/lang-tag-apps.htm for + further information. + + + + + + + + + + + + + + + See http://www.w3.org/TR/xmlbase/ for + information about this attribute. + + + + + + See http://www.w3.org/TR/xml-id/ for + information about this attribute. + + + + + + + + + + \ No newline at end of file diff --git a/pymavlink/generator/lib/minixsv/xsvalBase.py b/pymavlink/generator/lib/minixsv/xsvalBase.py new file mode 100644 index 0000000..9366214 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/xsvalBase.py @@ -0,0 +1,1280 @@ +# +# minixsv, Release 0.9.0 +# file: xsvalBase.py +# +# XML schema validator base class +# +# history: +# 2004-10-07 rl created +# 2006-08-18 rl W3C testsuite passed for supported features +# 2007-06-14 rl Features for release 0.8 added, several bugs fixed +# +# Copyright (c) 2004-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The minixsv XML schema validator is +# +# Copyright (c) 2004-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import string +import copy +from ..minixsv import * +from ..genxmlif.xmlifUtils import collapseString, convertToAbsUrl, NsNameTupleFactory, NsNameTuple +from xsvalSimpleTypes import XsSimpleTypeVal, SimpleTypeError + + +wxsdTree = None +wxsdLookupDict = {} + + +########################################################## +# Validator class for validating one input file against one XML schema file + +class XsValBase: + + def __init__(self, xmlIf, errorHandler, verbose): + self.xmlIf = xmlIf + self.errorHandler = errorHandler + self.verbose = verbose + + self._raiseError = self.errorHandler.raiseError + self._addError = self.errorHandler.addError + self._addWarning = self.errorHandler.addWarning + self._addInfo = self.errorHandler.addInfo + + self.checkKeyrefList = [] + + + def unlink(self): + self.simpleTypeVal.unlink() + + + ######################################## + # validate inputTree against xsdTree + # + def validate (self, inputTree, xsdTreeList): + self.inputTree = inputTree + + self.inputRoot = self.inputTree.getRootNode() + + self.inputNsURI = self.inputRoot.getNamespaceURI() + self.inputNsPrefix = self.inputRoot.getNsPrefix(self.inputRoot.getNsName()) + if self.inputNsPrefix != None: + self.inputNsPrefixString = "%s:" %(self.inputNsPrefix) + else: + self.inputNsPrefixString = "" + + # initialise lookup dictionary + global wxsdLookupDict + if wxsdLookupDict == {}: + wxsdLookupDict = {"ElementDict":{}, "TypeDict":{}, "GroupDict":{}, + "AttrGroupDict":{}, "AttributeDict":{}, "IdentityConstrDict":{}} + self._importWellknownSchemas(wxsdLookupDict) + + self.xsdLookupDict = {"ElementDict": wxsdLookupDict["ElementDict"].copy(), + "TypeDict": wxsdLookupDict["TypeDict"].copy(), + "GroupDict": wxsdLookupDict["GroupDict"].copy(), + "AttrGroupDict": wxsdLookupDict["AttrGroupDict"].copy(), + "AttributeDict": wxsdLookupDict["AttributeDict"].copy(), + "IdentityConstrDict": wxsdLookupDict["IdentityConstrDict"].copy()} + self.xsdElementDict = self.xsdLookupDict["ElementDict"] + self.xsdTypeDict = self.xsdLookupDict["TypeDict"] + self.xsdGroupDict = self.xsdLookupDict["GroupDict"] + self.xsdAttrGroupDict = self.xsdLookupDict["AttrGroupDict"] + self.xsdAttributeDict = self.xsdLookupDict["AttributeDict"] + self.xsdIdentityConstrDict = self.xsdLookupDict["IdentityConstrDict"] + + self.xsdIdDict = {} + self.xsdIdRefDict = {} + self.idAttributeForType = None + + for xsdTree in xsdTreeList: + xsdRoot = xsdTree.getRootNode() + + # TODO: The following member may differ if several schema files are used!! + self.xsdNsURI = xsdRoot.getNamespaceURI() + + self.xsdIncludeDict = {xsdRoot.getAbsUrl():1,} + if xsdRoot.getFilePath() != os.path.join (MINIXSV_DIR, "XMLSchema.xsd"): + self._initInternalAttributes (xsdRoot) + self._updateLookupTables(xsdRoot, self.xsdLookupDict) + + self._includeAndImport (xsdTree, xsdTree, self.xsdIncludeDict, self.xsdLookupDict) + + + self.simpleTypeVal = XsSimpleTypeVal(self) + + inputRootNsName = self.inputRoot.getNsName() + if self.xsdElementDict.has_key(inputRootNsName): + # start recursive schema validation + try: + self._checkElementTag (self.xsdElementDict[inputRootNsName], self.inputRoot, (self.inputRoot,), 0) + except TagException, errInst: + self._addError (errInst.errstr, errInst.node, errInst.endTag) + + if not self.errorHandler.hasErrors(): + # validate IDREFs + for idref in self.xsdIdRefDict.keys(): + if not self.xsdIdDict.has_key(idref): + self._addError ("There is no ID/IDREF binding for IDREF %s" %repr(idref), self.xsdIdRefDict[idref]) + + # validate keyrefs + for inputElement, keyrefNode in self.checkKeyrefList: + self._checkKeyRefConstraint (keyrefNode, inputElement) + else: + self._raiseError ("Used root tag %s not found in schema file(s)!" + %repr(inputRootNsName), self.inputRoot) + + + ######################################## + # include/import all files specified in the schema file + # import well-known schemas + # + def _includeAndImport (self, baseTree, tree, includeDict, lookupDict): + self._expandIncludes (baseTree, tree, includeDict, lookupDict) + self._expandRedefines (baseTree, tree, includeDict, lookupDict) + self._expandImports (baseTree, tree, includeDict, lookupDict) + + + ######################################## + # expand include directives + # + def _expandIncludes (self, baseTree, tree, includeDict, lookupDict): + rootNode = tree.getRootNode() + namespaceURI = rootNode.getNamespaceURI() + for includeNode in rootNode.getChildrenNS(namespaceURI, "include"): + includeUrl = includeNode.getAttribute("schemaLocation") + expNamespace = rootNode.getAttributeOrDefault("targetNamespace", None) + self._includeSchemaFile (baseTree, tree, includeNode, expNamespace, includeUrl, includeNode.getBaseUrl(), includeDict, lookupDict, + adaptTargetNamespace=1) + rootNode.removeChild (includeNode) + + + ######################################## + # expand redefine directives + # + def _expandRedefines (self, baseTree, tree, includeDict, lookupDict): + rootNode = tree.getRootNode() + namespaceURI = rootNode.getNamespaceURI() + + for redefineNode in rootNode.getChildrenNS(namespaceURI, "redefine"): + redefineUrl = redefineNode.getAttribute("schemaLocation") + expNamespace = rootNode.getAttributeOrDefault("targetNamespace", None) + self._includeSchemaFile (baseTree, tree, redefineNode, expNamespace, redefineUrl, redefineNode.getBaseUrl(), includeDict, lookupDict, + adaptTargetNamespace=1) + + # fill lookup tables with redefined definitions + for childNode in redefineNode.getChildren(): + redefineNode.removeChild(childNode) + rootNode.insertBefore(childNode, redefineNode) + + if childNode.getLocalName() in ("complexType", "simpleType"): + xsdDict = self.xsdLookupDict["TypeDict"] + elif childNode.getLocalName() in ("attributeGroup"): + xsdDict = self.xsdLookupDict["AttrGroupDict"] + elif childNode.getLocalName() in ("group"): + xsdDict = self.xsdLookupDict["GroupDict"] + elif childNode.getLocalName() in ("annotation"): + continue + else: + self._addError ("%s not allowed as child of 'redefine'!" %repr(childNode.getLocalName()), childNode) + continue + + redefType = NsNameTuple ( (expNamespace, childNode.getAttribute("name")) ) + if xsdDict.has_key(redefType): + orgRedefType = NsNameTuple( (expNamespace, redefType[1]+"__ORG") ) + if not xsdDict.has_key(orgRedefType): + xsdDict[orgRedefType] = xsdDict[redefType] +# else: +# self._addError ("Duplicate component %s found within 'redefine'!" %repr(redefType), childNode) + xsdDict[redefType] = childNode + else: + self._addError ("Type %s not found in imported schema file!" %(repr(redefType)), childNode) + + dummy, attrNodes, attrNsNameFirst = childNode.getXPathList (".//@base | .//@ref" % vars()) + for attrNode in attrNodes: + if attrNode.hasAttribute("base"): + attribute = "base" + elif attrNode.hasAttribute("ref"): + attribute = "ref" + if attrNode.getQNameAttribute(attribute) == redefType: + attrNode[attribute] = attrNode[attribute] + "__ORG" + + rootNode.removeChild (redefineNode) + + + ######################################## + # expand import directives + # + def _expandImports (self, baseTree, tree, includeDict, lookupDict): + rootNode = tree.getRootNode() + namespaceURI = rootNode.getNamespaceURI() + + for includeNode in rootNode.getChildrenNS(namespaceURI, "import"): + expNamespace = includeNode.getAttributeOrDefault("namespace", None) + if expNamespace == self._getTargetNamespace(includeNode): + self._addError ("Target namespace and target namespace of imported schema must not be the same!", includeNode) + continue + + includeUrl = includeNode.getAttributeOrDefault("schemaLocation", None) + if expNamespace != None and includeUrl == None: + includeUrl = expNamespace + ".xsd" + if includeUrl != None: + if expNamespace not in (XML_NAMESPACE, XSI_NAMESPACE): + self._includeSchemaFile (baseTree, tree, includeNode, expNamespace, includeUrl, includeNode.getBaseUrl(), includeDict, lookupDict) + else: + self._addError ("schemaLocation attribute for import directive missing!", includeNode) + rootNode.removeChild (includeNode) + + + ######################################## + # import well-known schema files + # + def _importWellknownSchemas (self, lookupDict): + global wxsdTree + file = os.path.join (MINIXSV_DIR, "XMLSchema.xsd") + wxsdTree = self.xmlIf.parse (file) + self._initInternalAttributes (wxsdTree.getRootNode()) + self._updateLookupTables (wxsdTree.getRootNode(), lookupDict) + + for schemaFile in ("datatypes.xsd", "xml.xsd", "XMLSchema-instance.xsd"): + file = os.path.join (MINIXSV_DIR, schemaFile) + subTree = self._parseIncludeSchemaFile(wxsdTree, wxsdTree, None, file, None) + self._updateLookupTables (subTree.getRootNode(), lookupDict) + + + ######################################## + # include/import a schema file + # + def _includeSchemaFile (self, baseTree, tree, nextSibling, expNamespace, includeUrl, baseUrl, includeDict, lookupDict, + adaptTargetNamespace=0): + if includeUrl == None: + self._raiseError ("Schema location attribute missing!", nextSibling) + absUrl = convertToAbsUrl (includeUrl, baseUrl) + if includeDict.has_key (absUrl): + # file already included + return + + if self.verbose: + print "including %s..." %(includeUrl) + rootNode = tree.getRootNode() + + subTree = self._parseIncludeSchemaFile(baseTree, tree, nextSibling, includeUrl, baseUrl) + includeDict[absUrl] = 1 + + stRootNode = subTree.getRootNode() + if rootNode.getNsName() != stRootNode.getNsName(): + self._raiseError ("Root tag of file %s does not match!" %repr(includeUrl), nextSibling) + + if stRootNode.hasAttribute("targetNamespace"): + if expNamespace != stRootNode["targetNamespace"]: + self._raiseError ("Target namespace of file %s does not match!" %repr(includeUrl), nextSibling) + else: + if expNamespace != None: + if adaptTargetNamespace: + # if no target namespace is specified in the included file + # the target namespace of the parent file is taken + stRootNode["targetNamespace"] = expNamespace + for stDescNode in stRootNode.getIterator(): + stDescNode.curNs.append((EMPTY_PREFIX,expNamespace)) + else: + self._raiseError ("Target namespace of file %s does not match!" %repr(includeUrl), nextSibling) + + self._updateLookupTables (subTree.getRootNode(), lookupDict) + self._includeAndImport (baseTree, subTree, includeDict, lookupDict) + if includeUrl not in (r"C:\Program Files\Python24\Lib\site-packages\minixsv\xml.xsd", + r"C:\Program Files\Python24\Lib\site-packages\minixsv\XMLSchema.xsd", + r"C:\Program Files\Python24\Lib\site-packages\minixsv\XMLSchema-instance.xsd"): + rootNode.insertSubtree (nextSibling, subTree, insertSubTreeRootNode=0) + + + def _parseIncludeSchemaFile (self, baseTree, tree, nextSibling, includeUrl, baseUrl): + # try to parse included schema file + try: + subTree = self.xmlIf.parse (includeUrl, baseUrl, baseTree.getTree()) + self._initInternalAttributes (subTree.getRootNode()) + except IOError, errInst: + self._raiseError ("%s" %str(errInst), nextSibling) + except SyntaxError, e: + # FIXME: sometimes an URLError is catched instead of a standard IOError + try: + dummy = e.errno + except: + raise IOError, e + + if e.errno in (2, "socket error", "url error"): # catch IOError: No such file or directory + self._raiseError ("%s: '%s'" %(e.strerror, e.filename), nextSibling) + else: + raise + + return subTree + + ######################################## + # update lookup dictionaries used during validation + # + def _updateLookupTables (self, rootNode, lookupDict): + schemaTagDict = {"element" : "ElementDict", + "complexType": "TypeDict", + "simpleType" : "TypeDict", + "group" : "GroupDict", + "attributeGroup": "AttrGroupDict", + "attribute" : "AttributeDict", + } + + # retrieve all schema tags + for localName, lookupDictName in schemaTagDict.items(): + for node in rootNode.getChildrenNS(XSD_NAMESPACE, localName): + targetNamespace = self._getTargetNamespace(node) + if not lookupDict[lookupDictName].has_key((targetNamespace, node.getAttribute("name"))): + lookupDict[lookupDictName][(targetNamespace, node.getAttribute("name"))] = node + + # retrieve all identity constraints + for identConstrTagName in ("unique", "key", "keyref"): + identConstrNodeList = rootNode.getElementsByTagNameNS (XSD_NAMESPACE, identConstrTagName) + for identConstrNode in identConstrNodeList: + targetNamespace = self._getTargetNamespace(identConstrNode) + identConstrNsLocalName = NsNameTupleFactory ( (targetNamespace, identConstrNode.getAttribute("name")) ) + if not lookupDict["IdentityConstrDict"].has_key(identConstrNsLocalName): + lookupDict["IdentityConstrDict"][identConstrNsLocalName] = {"Node": identConstrNode, "ValueDict":{}} + +# else: +# self._addError ("Duplicate identity constraint name %s found!" +# %(repr(identConstrNsLocalName)), identConstrNode) + + ######################################## + # validate inputNode against complexType node + # + def _initInternalAttributes (self, rootNode): + # set schema root node for all descendant nodes + if not rootNode.getSchemaRootNode(): + for node in rootNode.getIterator(): + node.setSchemaRootNode(rootNode) + + + ######################################## + # validate inputNode against complexType node + # + def _checkComplexTypeTag (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType=None): + baseTypeAttributes = {} + + complexContentNode = xsdNode.getFirstChildNS(self.xsdNsURI, "complexContent") + simpleContentNode = xsdNode.getFirstChildNS(self.xsdNsURI, "simpleContent") + if complexContentNode != None: + inputChildIndex, baseTypeAttributes = self._checkComplexContentTag (xsdParentNode, complexContentNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + elif simpleContentNode != None: + inputChildIndex, baseTypeAttributes = self._checkSimpleContentTag (xsdParentNode, simpleContentNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + else: + inputChildIndex, baseTypeAttributes = self._checkComplexTypeContent (xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + if usedAsBaseType == None: + self._checkMixed (xsdParentNode, xsdNode, inputNode) + return inputChildIndex, baseTypeAttributes + + def _checkComplexContentTag (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + extensionNode = xsdNode.getFirstChildNS(self.xsdNsURI, "extension") + if extensionNode != None: + inputChildIndex, baseTypeAttributes = self._checkExtensionComplexContent (xsdParentNode, extensionNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + else: + restrictionNode = xsdNode.getFirstChildNS(self.xsdNsURI, "restriction") + if restrictionNode != None: + inputChildIndex, baseTypeAttributes = self._checkRestrictionComplexContent (xsdParentNode, restrictionNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + else: + raise AttributeError, "RestrictionNode not found!" + +# if usedAsBaseType == None: +# self._checkMixed (xsdNode, inputNode) + return inputChildIndex, baseTypeAttributes + + def _checkSimpleContentTag (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + if inputNode.getAttribute( (XSI_NAMESPACE, "nil") ) == "true": + if inputNode.getChildren() != [] or collapseString(inputNode.getElementValue()) != "": + self._addError ("Element must be empty (xsi:nil='true')(1)!" , inputNode, 0) + + extensionNode = xsdNode.getFirstChildNS(self.xsdNsURI, "extension") + if extensionNode != None: + inputChildIndex, baseTypeAttributes = self._checkExtensionSimpleContent (xsdParentNode, extensionNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + else: + restrictionNode = xsdNode.getFirstChildNS(self.xsdNsURI, "restriction") + if restrictionNode != None: + inputChildIndex, baseTypeAttributes = self._checkRestrictionSimpleContent (xsdParentNode, xsdNode, restrictionNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + return inputChildIndex, baseTypeAttributes + + def _checkExtensionComplexContent (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + baseNsName = xsdNode.getQNameAttribute("base") + if usedAsBaseType == None: + extUsedAsBaseType = "extension" + else: + extUsedAsBaseType = usedAsBaseType + inputChildIndex, baseTypeAttributes = self._checkComplexTypeTag (xsdParentNode, self.xsdTypeDict[baseNsName], inputNode, inputChildIndex, extUsedAsBaseType) + + inputChildIndex, baseTypeAttributes = self._checkComplexTypeContent (xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + return inputChildIndex, baseTypeAttributes + + def _checkExtensionSimpleContent (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + self._checkSimpleType (xsdNode, "base", inputNode, inputNode.getTagName(), inputNode.getElementValue(), None, checkAttribute=0) + if xsdNode.hasAttribute("BaseTypes"): + xsdParentNode["BaseTypes"] = xsdNode["BaseTypes"] + inputChildIndex, baseTypeAttributes = self._checkSimpleTypeContent (xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + return inputChildIndex, baseTypeAttributes + + def _checkRestrictionComplexContent (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + # first check against base type (retrieve only the base type attributes) + baseNsName = xsdNode.getQNameAttribute("base") + inputChildIndex, baseTypeAttributes = self._checkComplexTypeTag (xsdParentNode, self.xsdTypeDict[baseNsName], inputNode, inputChildIndex, "restriction") + + # then check input against derived complex type + inputChildIndex, baseTypeAttributes = self._checkComplexTypeContent (xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + return inputChildIndex, baseTypeAttributes + + def _checkRestrictionSimpleContent (self, xsdParentNode, simpleContentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + try: + simpleTypeReturnDict = {"BaseTypes":[], "primitiveType":None} + self.simpleTypeVal.checkSimpleTypeDef (inputNode, simpleContentNode, inputNode.getTagName(), inputNode.getElementValue(), simpleTypeReturnDict, idCheck=1) + xsdNode["BaseTypes"] = string.join (simpleTypeReturnDict["BaseTypes"], " ") + except SimpleTypeError, errInst: + self._addError (errInst.args[0], inputNode) + + inputChildIndex, baseTypeAttributes = self._checkSimpleTypeContent (xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes) + return inputChildIndex, baseTypeAttributes + + def _checkComplexTypeContent (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + if inputNode.getAttribute((XSI_NAMESPACE, "nil")) == "true": + if inputNode.getChildren() != [] or collapseString(inputNode.getElementValue()) != "": + self._addError ("Element must be empty (xsi:nil='true')(2)!" , inputNode, 0) + else: + childTags = inputNode.getChildren() + if usedAsBaseType in (None, "extension"): + validChildTags = xsdNode.getChildren() + for validChildTag in validChildTags: + if validChildTag.getLocalName() not in ("attribute", "attributeGroup", "anyAttribute"): + inputChildIndex = self._checkParticle (validChildTag, inputNode, childTags, inputChildIndex) + + if usedAsBaseType == None and inputChildIndex < len (childTags): + inputNsName = inputNode.getNsName() + childNsName = childTags[inputChildIndex].getNsName() + self._addError ("Unexpected or invalid child tag %s found in tag %s!" + %(repr(childNsName), repr(inputNsName)), childTags[inputChildIndex]) + + if usedAsBaseType in (None,): + self._checkAttributeTags (xsdParentNode, xsdNode, inputNode, baseTypeAttributes) + + if usedAsBaseType in ("restriction", "extension"): + self._updateAttributeDict (xsdNode, baseTypeAttributes) + + return inputChildIndex, baseTypeAttributes + + def _checkSimpleTypeContent (self, xsdParentNode, xsdNode, inputNode, inputChildIndex, usedAsBaseType, baseTypeAttributes): + if inputNode.getChildren() != []: + raise TagException ("No child tags are allowed for element %s!" %repr(inputNode.getNsName()), inputNode) + + if usedAsBaseType in (None,): + self._checkAttributeTags (xsdParentNode, xsdNode, inputNode, baseTypeAttributes) + + if usedAsBaseType in ("restriction", "extension"): + self._updateAttributeDict (xsdNode, baseTypeAttributes) + + return inputChildIndex, baseTypeAttributes + + + ######################################## + # validate mixed content (1) + # + def _checkMixed (self, xsdParentNode, xsdNode, inputNode): + if xsdNode.getAttributeOrDefault ("mixed", "false") == "false": + if not collapseString(inputNode.getElementValue()) in ("", " "): + self._addError ("Mixed content not allowed for %s!" %repr(inputNode.getTagName()), inputNode) + else: # mixed = true + self._checkUrType(xsdParentNode, inputNode) + + + ######################################## + # check ur-type + # + def _checkUrType (self, xsdNode, inputNode): + prefix = xsdNode.getPrefix() + if prefix: + xsdNode["__CONTENTTYPE__"] = "%s:string" %xsdNode.getPrefix() + else: + xsdNode["__CONTENTTYPE__"] = "string" + self._checkElementValue (xsdNode, "__CONTENTTYPE__", inputNode) + xsdNode.removeAttribute("__CONTENTTYPE__") + + + ######################################## + # validate inputNodeList against xsdNode + # + def _checkList (self, elementMethod, xsdNode, inputParentNode, inputNodeList, currIndex): + minOccurs = string.atoi(xsdNode.getAttributeOrDefault("minOccurs", "1")) + maxOccurs = xsdNode.getAttributeOrDefault("maxOccurs", "1") + if maxOccurs != "unbounded": + maxOccurs = string.atoi(maxOccurs) + else: + maxOccurs = -1 + occurs = 0 + while maxOccurs == -1 or occurs < maxOccurs: + try: + newIndex = elementMethod (xsdNode, inputParentNode, inputNodeList, currIndex) + occurs += 1 + if newIndex > currIndex: + currIndex = newIndex + else: + break # no suitable element found + except TagException, errInst: + break + + if occurs == 0 and minOccurs > 0: + raise errInst + elif occurs < minOccurs: + expInputTagName = xsdNode.getAttribute("name") + if expInputTagName == None: + expInputTagName = xsdNode.getQNameAttribute("ref") + raise TagException ("minOccurs (%d) of child tag %s in tag %s not available (only %d)!" + %(minOccurs, repr(expInputTagName), repr(inputParentNode.getTagName()), occurs), inputParentNode, 1) + + return currIndex + + ######################################## + # validate inputNode against element node + # + def _checkElementTag (self, xsdNode, inputParentNode, inputNodeList, currIndex): + if xsdNode.hasAttribute("ref"): + refNsName = xsdNode.getQNameAttribute("ref") + currIndex = self._checkElementTag (self.xsdElementDict[refNsName], inputParentNode, inputNodeList, currIndex) + else: + nameAttr = xsdNode.getAttribute ("name") + + if currIndex >= len (inputNodeList): + raise TagException ("Missing child tag %s in tag %s!" %(repr(nameAttr), repr(inputParentNode.getTagName())), inputParentNode, 1) + + inputNode = inputNodeList[currIndex] + if nameAttr != inputNode.getLocalName(): + raise TagException ("Missing child tag %s in tag %s!" %(repr(nameAttr), repr(inputParentNode.getTagName())), inputNode, 0) + + # store reference to XSD definition node + inputNode.setXsdNode(xsdNode) + + currIndex = currIndex + 1 + + self._checkInputElementForm (xsdNode, nameAttr, inputNode) + + if (xsdNode.getFirstChild() == None and + not xsdNode.hasAttribute("type") and + not inputNode.hasAttribute((XSI_NAMESPACE, "type")) ): + self._checkUrType(xsdNode, inputNode) + # ur-type => try to check children of input node + for inputChild in inputNode.getChildren(): + try: + if self.xsdElementDict.has_key(inputChild.getNsName()): + self._checkElementTag (self.xsdElementDict[inputChild.getNsName()], inputNode, (inputChild,), 0) + except TagException, errInst: + self._addError (errInst.errstr, errInst.node, errInst.endTag) + return currIndex + + complexTypeNode = xsdNode.getFirstChildNS (self.xsdNsURI, "complexType") + if not inputNode.hasAttribute((XSI_NAMESPACE, "type")): + typeNsName = xsdNode.getQNameAttribute ("type") + else: + # overloaded type is used + typeNsName = inputNode.getQNameAttribute((XSI_NAMESPACE, "type")) + if not self.xsdTypeDict.has_key(typeNsName): + self._addError ("Unknown overloaded type %s!" %(repr(typeNsName)), inputNode, 0) + return currIndex + + if self.xsdTypeDict.has_key (typeNsName): + typeType = self.xsdTypeDict[typeNsName].getLocalName() + if typeType == "complexType": + complexTypeNode = self.xsdTypeDict[typeNsName] + # else simpleType => pass, handled later on + + if complexTypeNode != None: + try: + self._checkComplexTypeTag (xsdNode, complexTypeNode, inputNode, 0) + except TagException, errInst: + self._addError (errInst.errstr, errInst.node, errInst.endTag) + return currIndex + else: + self._checkElementSimpleType (xsdNode, "type", inputNode) + + # check unique attributes and keys + childUniqueDefList = xsdNode.getChildrenNS (self.xsdNsURI, "unique") + for childUniqueDef in childUniqueDefList: + self._checkIdentityConstraint (childUniqueDef, inputNode) + + childKeyDefList = xsdNode.getChildrenNS (self.xsdNsURI, "key") + for childKeyDef in childKeyDefList: + self._checkIdentityConstraint (childKeyDef, inputNode) + + childKeyrefDefList = xsdNode.getChildrenNS (self.xsdNsURI, "keyref") + for childKeyrefDef in childKeyrefDefList: + self.checkKeyrefList.append ((inputNode, childKeyrefDef)) + + return currIndex + + + ######################################## + # validate element inputNode against simple type definition + # + def _checkElementSimpleType (self, xsdNode, xsdTypeAttr, inputNode): + if inputNode.getChildren() != []: + raise TagException ("No child tags are allowed for element %s!" %(repr(inputNode.getNsName())), inputNode) + + self._checkElementValue (xsdNode, xsdTypeAttr, inputNode) + + self._checkAttributeTags (xsdNode, xsdNode, inputNode, {}) + + + ######################################## + # validate inputNode against simple type definition + # + def _checkElementValue (self, xsdNode, xsdTypeAttr, inputNode): + fixedValue = xsdNode.getAttribute("fixed") + if inputNode.getAttribute((XSI_NAMESPACE, "nil")) == "true" and fixedValue != None: + self._addError ("There must be no fixed value for Element because xsi:nil='true' is specified!" , inputNode) + + if inputNode.getAttribute((XSI_NAMESPACE, "nil")) != "true" and inputNode.getElementValue() == "": + if xsdNode.hasAttribute("default"): + inputNode.setElementValue(xsdNode["default"]) + if fixedValue != None: + inputNode.setElementValue(fixedValue) + + self._checkSimpleType (xsdNode, xsdTypeAttr, inputNode, inputNode.getTagName(), inputNode.getElementValue(), fixedValue, checkAttribute=0) + + + ######################################## + # validate inputNode against simple type definition + # + def _checkSimpleType (self, xsdNode, xsdTypeAttr, inputNode, attrName, attrValue, fixedValue, checkAttribute=0, checkId=1): + retValue = None + + if checkAttribute == 0 and inputNode.hasAttribute((XSI_NAMESPACE, "nil")): + if (inputNode[(XSI_NAMESPACE, "nil")] == "true" and + collapseString(inputNode.getElementValue()) != ""): + self._addError ("Element must be empty (xsi:nil='true')(3)!" , inputNode, 0) + return retValue + + try: + simpleTypeReturnDict = {"BaseTypes":[], "primitiveType":None} + fixedValueReturnDict = {"BaseTypes":[], "primitiveType":None} + simpleTypeNode = xsdNode.getFirstChildNS (self.xsdNsURI, "simpleType") + if simpleTypeNode != None: + self.simpleTypeVal.checkSimpleTypeDef (inputNode, simpleTypeNode, attrName, attrValue, simpleTypeReturnDict, checkId) + if fixedValue != None: + self.simpleTypeVal.checkSimpleTypeDef (inputNode, simpleTypeNode, attrName, fixedValue, fixedValueReturnDict, idCheck=0) + elif (xsdNode.getFirstChildNS (self.xsdNsURI, "complexType") != None and + xsdNode.getFirstChildNS (self.xsdNsURI, "complexType").getAttribute("mixed") == "false"): + self._addError ("Attribute %s requires a simple or mixed type!" %repr(attrName), inputNode) + else: + typeNsName = xsdNode.getQNameAttribute (xsdTypeAttr) + if typeNsName != (None, None): + self.simpleTypeVal.checkSimpleType (inputNode, attrName, typeNsName, attrValue, simpleTypeReturnDict, checkId) + # TODO: What to check if no type is specified for the element? + if fixedValue != None: + self.simpleTypeVal.checkSimpleType (inputNode, attrName, typeNsName, fixedValue, fixedValueReturnDict, idCheck=0) + + xsdNode["BaseTypes"] = string.join (simpleTypeReturnDict["BaseTypes"], " ") + xsdNode["primitiveType"] = str(simpleTypeReturnDict["primitiveType"]) + + retValue = simpleTypeReturnDict + if simpleTypeReturnDict.has_key("wsAction"): + if checkAttribute: + attrValue = inputNode.processWsAttribute(attrName, simpleTypeReturnDict["wsAction"]) + else: + attrValue = inputNode.processWsElementValue(simpleTypeReturnDict["wsAction"]) + + if fixedValue != None: + if fixedValueReturnDict.has_key("orderedValue"): + fixedValue = fixedValueReturnDict["orderedValue"] + elif fixedValueReturnDict.has_key("adaptedAttrValue"): + fixedValue = fixedValueReturnDict["adaptedAttrValue"] + if simpleTypeReturnDict.has_key("orderedValue"): + attrValue = simpleTypeReturnDict["orderedValue"] + if attrValue != fixedValue: + if checkAttribute: + self._addError ("Attribute %s must have fixed value %s!" %(repr(attrName), repr(fixedValue)), inputNode) + else: + self._addError ("Element must have fixed value %s!" %repr(fixedValue), inputNode) + + except SimpleTypeError, errInst: + self._addError (errInst.args[0], inputNode) + + return retValue + + ######################################## + # validate inputNode against sequence node + # + def _checkSequenceTag (self, xsdNode, inputParentNode, inputNodeList, currIndex): + for xsdChildNode in xsdNode.getChildren(): + currIndex = self._checkParticle (xsdChildNode, inputParentNode, inputNodeList, currIndex) + return currIndex + + + ######################################## + # validate inputNode against choice node + # + def _checkChoiceTag (self, xsdNode, inputParentNode, inputNodeList, currIndex): + childFound = 0 + exceptionRaised = 0 + for xsdChildNode in xsdNode.getChildren(): + try: + newIndex = self._checkParticle (xsdChildNode, inputParentNode, inputNodeList, currIndex) + if newIndex > currIndex: + currIndex = newIndex + childFound = 1 + break + else: + exceptionRaised = 0 + except TagException, errInst: + exceptionRaised = 1 + else: + if not childFound and exceptionRaised: + if currIndex < len(inputNodeList): + currNode = inputNodeList[currIndex] + endTag = 0 + else: + currNode = inputParentNode + endTag = 1 + raise TagException ("No suitable child tag for choice found!", currNode, endTag) + + return currIndex + + + ######################################## + # validate inputNode against group node + # + def _checkGroupTag (self, xsdNode, inputParentNode, inputNodeList, currIndex): + if xsdNode.hasAttribute("ref"): + refNsName = xsdNode.getQNameAttribute("ref") + currIndex = self._checkGroupTag (self.xsdGroupDict[refNsName], inputParentNode, inputNodeList, currIndex) + else: + for xsdChildNode in xsdNode.getChildren(): + currIndex = self._checkParticle (xsdChildNode, inputParentNode, inputNodeList, currIndex) + return currIndex + + + ######################################## + # validate inputNode against all node + # + def _checkAllTag (self, xsdNode, inputParentNode, inputNodeList, currIndex): + oldIndex = currIndex + xsdChildDict = {} + for xsdChildNode in xsdNode.getChildren(): + if xsdChildNode.getNsName() != (XSD_NAMESPACE, "annotation"): + xsdChildDict[xsdChildNode] = 0 + while (currIndex < len(inputNodeList)) and (0 in xsdChildDict.values()): + currNode = inputNodeList[currIndex] + for xsdChildNode in xsdChildDict.keys(): + try: + newIndex = self._checkParticle (xsdChildNode, inputParentNode, inputNodeList, currIndex) + if newIndex == currIndex: + continue + except TagException, errInst: + continue + + if xsdChildDict[xsdChildNode] == 0: + xsdChildDict[xsdChildNode] = 1 + currIndex = newIndex + break + else: + raise TagException ("Ambiguous child tag %s found in all-group!" %repr(currNode.getTagName()), currNode) + else: + raise TagException ("Unexpected child tag %s for all-group found!" %repr(currNode.getTagName()), currNode) + + for xsdChildNode, occurs in xsdChildDict.items(): + if xsdChildNode.getAttributeOrDefault("minOccurs", "1") != "0" and occurs == 0: + raise TagException ("Child tag %s missing in all-group (%s)" %(repr(xsdChildNode.getAttribute("name")), repr(inputParentNode.getTagName())), inputParentNode) + + return currIndex + + + ######################################## + # validate inputNode against any node + # + def _checkAnyTag (self, xsdNode, inputParentNode, inputNodeList, currIndex): + if currIndex >= len (inputNodeList): + raise TagException ("Missing child tag (anyTag) in tag %s!" %repr(inputParentNode.getTagName()), inputParentNode, 1) + + inputNode = inputNodeList[currIndex] + inputNamespace = inputNode.getNamespaceURI() + self._checkWildcardElement (xsdNode, inputNode, inputNamespace) + + currIndex = currIndex + 1 + return currIndex + + + ######################################## + # validate inputNode against particle + # + def _checkParticle (self, xsdNode, inputParentNode, inputNodeList, currIndex): + xsdTagName = xsdNode.getLocalName() + if xsdTagName == "element": + currIndex = self._checkList (self._checkElementTag, xsdNode, inputParentNode, inputNodeList, currIndex) + elif xsdTagName == "choice": + currIndex = self._checkList (self._checkChoiceTag, xsdNode, inputParentNode, inputNodeList, currIndex) + elif xsdTagName == "sequence": + currIndex = self._checkList (self._checkSequenceTag, xsdNode, inputParentNode, inputNodeList, currIndex) + elif xsdTagName == "group": + currIndex = self._checkList (self._checkGroupTag, xsdNode, inputParentNode, inputNodeList, currIndex) + elif xsdTagName == "all": + currIndex = self._checkList (self._checkAllTag, xsdNode, inputParentNode, inputNodeList, currIndex) + elif xsdTagName == "any": + currIndex = self._checkList (self._checkAnyTag, xsdNode, inputParentNode, inputNodeList, currIndex) + elif xsdTagName == "annotation": + # TODO: really nothing to check?? + pass + else: + self._addError ("Internal error: Invalid tag %s found!" %repr(xsdTagName)) + return currIndex + + + ######################################## + # validate attributes of inputNode against complexType node + # + def _checkAttributeTags (self, parentNode, xsdNode, inputNode, validAttrDict): + # retrieve all valid attributes for this element from the schema file + self._updateAttributeDict (xsdNode, validAttrDict) + inputAttrDict = {} + for iAttrName, iAttrValue in inputNode.getAttributeDict().items(): + # skip namespace declarations + if iAttrName[0] != XMLNS_NAMESPACE and iAttrName[1] != "xmlns": + inputAttrDict[iAttrName] = iAttrValue + + for qAttrName, validAttrEntry in validAttrDict.items(): + attrRefNode = validAttrEntry["RefNode"] + # global attributes use always form "qualified" + if self.xsdAttributeDict.has_key(qAttrName) and self.xsdAttributeDict[qAttrName] == attrRefNode: + attributeForm = "qualified" + else: + attributeForm = attrRefNode.getAttributeOrDefault ("form", self._getAttributeFormDefault(xsdNode)) + attrRefNode.setAttribute ("form", attributeForm) + self._checkAttributeTag (qAttrName, validAttrEntry["Node"], attrRefNode, inputNode, inputAttrDict) + + for inputAttribute in inputAttrDict.keys(): + if inputAttribute == (XSI_NAMESPACE, "type"): + pass # for attribute xsi:type refer _checkElementTag + elif inputAttribute == (XSI_NAMESPACE, "nil"): + if parentNode.getAttributeOrDefault ("nillable", "false") == "false": + self._addError ("Tag %s hasn't been defined as nillable!" %repr(inputNode.getTagName()), inputNode) + elif inputNode == self.inputRoot and inputAttribute in ((XSI_NAMESPACE, "noNamespaceSchemaLocation"), (XSI_NAMESPACE, "schemaLocation")): + pass + elif validAttrDict.has_key("__ANY_ATTRIBUTE__"): + xsdNode = validAttrDict["__ANY_ATTRIBUTE__"]["Node"] + try: + inputNamespace = inputAttribute[0] + if inputAttribute[0] == None and xsdNode.getAttribute("form") == "unqualified": + # TODO: Check: If only local namespace is allowed, do not use target namespace??? + if xsdNode.getAttribute("namespace") != "##local": + inputNamespace = self._getTargetNamespace(xsdNode) + self._checkWildcardAttribute (xsdNode, inputNode, inputAttribute, inputNamespace, inputAttrDict) + except TagException: + self._addError ("Unexpected attribute %s in Tag %s!" %(repr(inputAttribute), repr(inputNode.getTagName())), inputNode) + else: + self._addError ("Unexpected attribute %s in Tag %s!" %(repr(inputAttribute), repr(inputNode.getTagName())), inputNode) + + + ######################################## + # validate one attribute (defined by xsdNode) of inputNode + # + def _checkAttributeTag (self, qAttrName, xsdAttrNode, xsdAttrRefNode, inputNode, inputAttrDict): + targetNamespace = self._getTargetNamespace(xsdAttrNode) + if qAttrName[0] == targetNamespace and xsdAttrRefNode.getAttribute("form") == "unqualified": + qAttrName = NsNameTupleFactory( (None, qAttrName[1]) ) + + use = xsdAttrNode.getAttribute("use") + if use == None: use = xsdAttrRefNode.getAttributeOrDefault ("use", "optional") + fixedValue = xsdAttrNode.getAttribute("fixed") + if fixedValue == None: + fixedValue = xsdAttrRefNode.getAttribute("fixed") + + if inputAttrDict.has_key(qAttrName): + if use == "prohibited": + self._addError ("Attribute %s is prohibited in this context!" %repr(qAttrName[1]), inputNode) + elif inputAttrDict.has_key((targetNamespace, qAttrName[1])): + self._addError ("Local attribute %s must be unqualified!" %(repr(qAttrName)), inputNode) + del inputAttrDict[(targetNamespace, qAttrName[1])] + elif inputAttrDict.has_key((None, qAttrName[1])) and qAttrName[0] == targetNamespace: + self._addError ("Attribute %s must be qualified!" %repr(qAttrName[1]), inputNode) + del inputAttrDict[(None, qAttrName[1])] + else: + if use == "required": + self._addError ("Attribute %s is missing!" %(repr(qAttrName)), inputNode) + elif use == "optional": + if xsdAttrRefNode.hasAttribute("default"): + if not (inputNode.getNsName() == (XSD_NAMESPACE, "element") and + inputNode.hasAttribute("ref") and + xsdAttrRefNode.getAttribute("name") == "nillable"): + defaultValue = xsdAttrRefNode.getAttribute("default") + inputNode.setAttribute(qAttrName, defaultValue) + inputAttrDict[qAttrName] = defaultValue + elif fixedValue != None: + inputNode.setAttribute(qAttrName, fixedValue) + inputAttrDict[qAttrName] = fixedValue + + if inputAttrDict.has_key(qAttrName): + attributeValue = inputAttrDict[qAttrName] + self._checkSimpleType (xsdAttrRefNode, "type", inputNode, qAttrName, attributeValue, fixedValue, 1) + del inputAttrDict[qAttrName] + inputNode.setXsdAttrNode(qAttrName, xsdAttrRefNode) + + + ######################################## + # update dictionary of valid attributes + # + def _updateAttributeDict (self, xsdNode, validAttrDict, checkForDuplicateAttr=0, recursionKeys=None): + # TODO: Why can recursionKeys not be initialized by default variable?? + if recursionKeys == None: recursionKeys = {} + validAttributeNodes = xsdNode.getChildrenNS(self.xsdNsURI, "attribute") + for validAttrGroup in xsdNode.getChildrenNS(self.xsdNsURI, "attributeGroup"): + refNsName = validAttrGroup.getQNameAttribute("ref") + if self.xsdAttrGroupDict.has_key(refNsName): + if recursionKeys.has_key(refNsName): + self._addError ("Circular definition for attribute group %s detected!" %(repr(refNsName)), validAttrGroup) + continue + recursionKeys[refNsName] = 1 + self._updateAttributeDict(self.xsdAttrGroupDict[refNsName], validAttrDict, checkForDuplicateAttr, recursionKeys) + + + for validAttributeNode in validAttributeNodes: + if validAttributeNode.hasAttribute("ref"): + attrKey = validAttributeNode.getQNameAttribute("ref") + attributeRefNode = self.xsdAttributeDict[attrKey] + else: + attrKey = validAttributeNode.getQNameAttribute("name") + attrKey = (self._getTargetNamespace(validAttributeNode), validAttributeNode.getAttribute("name")) + attributeRefNode = validAttributeNode + + if checkForDuplicateAttr and validAttrDict.has_key(attrKey): + self._addError ("Duplicate attribute %s found!" %repr(attrKey), validAttributeNode) + else: + validAttrDict[attrKey] = {"Node":validAttributeNode, "RefNode":attributeRefNode} + + anyAttributeNode = xsdNode.getFirstChildNS(self.xsdNsURI, "anyAttribute") + if anyAttributeNode != None: + validAttrDict["__ANY_ATTRIBUTE__"] = {"Node":anyAttributeNode, "RefNode":anyAttributeNode} + + + ######################################## + # validate wildcard specification of anyElement + # + def _checkWildcardElement (self, xsdNode, inputNode, inputNamespace): + processContents = xsdNode.getAttributeOrDefault("processContents", "lax") + + self._checkInputNamespace (xsdNode, inputNode, inputNamespace) + + inputNsName = inputNode.getNsName() + if processContents == "skip": + pass + else: + if inputNode.hasAttribute((XSI_NAMESPACE, "type")): + # overloaded type is used + typeNsName = inputNode.getQNameAttribute((XSI_NAMESPACE, "type")) + if not self.xsdTypeDict.has_key(typeNsName): + self._addError ("Unknown overloaded type %s!" %(repr(typeNsName)), inputNode, 0) + else: + typeType = self.xsdTypeDict[typeNsName].getLocalName() + if typeType == "complexType": + try: + self._checkComplexTypeTag (None, self.xsdTypeDict[typeNsName], inputNode, 0) + except TagException, errInst: + self._addError (errInst.errstr, errInst.node, errInst.endTag) + else: + simpleTypeReturnDict = {"BaseTypes":[], "primitiveType":None} + try: + self.simpleTypeVal.checkSimpleType (inputNode, inputNode.getLocalName(), typeNsName, inputNode.getElementValue(), simpleTypeReturnDict, idCheck=1) + except SimpleTypeError, errInst: + self._addError (errInst.args[0], inputNode) + + elif self.xsdElementDict.has_key(inputNsName): + self._checkElementTag (self.xsdElementDict[inputNsName], None, (inputNode,), 0) + + elif processContents == "strict": + self._addError ("Element definition %s not found in schema file!" %repr(inputNsName), inputNode) + + + ######################################## + # validate wildcard specification of anyElement/anyAttribute + # + def _checkWildcardAttribute (self, xsdNode, inputNode, qAttrName, inputNamespace, inputAttrDict): + processContents = xsdNode.getAttributeOrDefault("processContents", "strict") + + self._checkInputNamespace (xsdNode, inputNode, inputNamespace) + + if processContents == "skip": + pass + elif processContents == "lax": + if self.xsdAttributeDict.has_key(qAttrName): + attrNode = self.xsdAttributeDict[qAttrName] + self._checkAttributeTag (qAttrName, attrNode, attrNode, inputNode, inputAttrDict) + elif processContents == "strict": + if self.xsdAttributeDict.has_key(qAttrName): + attrNode = self.xsdAttributeDict[qAttrName] + self._checkAttributeTag (qAttrName, attrNode, attrNode, inputNode, inputAttrDict) + else: + self._addError ("Attribute definition %s not found in schema file!" %repr(qAttrName), inputNode) + + + ######################################## + # validate wildcard specification of anyElement/anyAttribute + # + def _checkInputNamespace (self, xsdNode, inputNode, inputNamespace): + targetNamespace = self._getTargetNamespace(xsdNode) + namespaces = xsdNode.getAttributeOrDefault("namespace", "##any") + if namespaces == "##any": + pass # nothing to check + elif namespaces == "##other": + if inputNamespace == targetNamespace or inputNamespace == None: + raise TagException ("Node or attribute must not be part of target namespace or local!", inputNode) + else: + for namespace in string.split(collapseString(namespaces), " "): + if namespace == "##local" and inputNamespace == None: + break + elif namespace == "##targetNamespace" and inputNamespace == targetNamespace: + break + elif namespace == inputNamespace: + break + else: + raise TagException ("Node or attribute is not part of namespace %s!" %repr(namespaces), inputNode) + + + ######################################## + # validate unique and key definition + # + def _checkIdentityConstraint (self, identityConstrNode, inputNode): + identConstrTag = identityConstrNode.getLocalName() + identConstrName = identityConstrNode.getAttribute ("name") + identConstrNsLocalName = (self._getTargetNamespace(identityConstrNode), identConstrName) + selectorXPathNode = identityConstrNode.getFirstChildNS (self.xsdNsURI, "selector") + selectorNodeList, dummy, dummy = self._getXPath (inputNode, selectorXPathNode) + + valueDict = {} + for selectorNode in selectorNodeList: + fieldXPathNodeList = identityConstrNode.getChildrenNS (self.xsdNsURI, "field") + keyValue = [] + baseTypesList = [] + for fieldXPathNode in fieldXPathNodeList: + fieldChildList, attrNodeList, attrName = self._getXPath (selectorNode, fieldXPathNode, identConstrTag) + if len(fieldChildList) > 1: + self._addError ("The field xPath %s of %s %s must evaluate to exactly 0 or 1 node!" %(repr(fieldXPathNode["xpath"]), repr(identConstrTag), repr(identConstrName)), selectorNode) + return + + for fieldChild in fieldChildList: + if attrNodeList == []: + inputChild = fieldChild + try: + baseTypes = self._setBaseTypes(fieldChild.getXsdNode()) + except: + baseTypes = ((XSD_NAMESPACE, "anyType"),) + value = fieldChild.getElementValue() + else: + inputChild = attrNodeList[0] + try: + baseTypes = self._setBaseTypes(attrNodeList[0].getXsdAttrNode(attrName)) + except: + baseTypes = ((XSD_NAMESPACE, "anyType"),) + value = fieldChild + if baseTypes != None: + if baseTypes[0] in ((XSD_NAMESPACE, "anyType"), (XSD_NAMESPACE, "anySimpleType")): + overloadedType = inputChild.getQNameAttribute((XSI_NAMESPACE, "type")) + if overloadedType != (None, None): + baseTypes = [inputChild.getQNameAttribute((XSI_NAMESPACE, "type")),] + else: + self._addError ("Identity constraint does not have a simple type!", inputChild) + continue + + baseTypesList.append(baseTypes) + for baseType in baseTypes: + try: + value = self._getOrderedValue (inputChild, attrName, baseType, value) + break + except SimpleTypeError, errInst: + pass + keyValue.append (value) + + if keyValue != []: + keyValue = tuple(keyValue) + if not valueDict.has_key (keyValue): + valueDict[keyValue] = 1 + self.xsdIdentityConstrDict[identConstrNsLocalName]["ValueDict"][keyValue] = baseTypesList + else: + if len(keyValue) == 1: + self._addError ("Duplicate identity constraint values %s found for identity contraint %s!" %(repr(keyValue[0]), repr(identConstrName)), selectorNode) + else: + self._addError ("Duplicate identity constraint values %s found for identity contraint %s!" %(repr(keyValue), repr(identConstrName)), selectorNode) + + ######################################## + # validate unique and key definition + # + def _checkKeyRefConstraint (self, keyrefNode, inputNode): + keyRefName = keyrefNode.getAttribute ("name") + keyReference = keyrefNode.getQNameAttribute ("refer") + + selectorXPathNode = keyrefNode.getFirstChildNS (self.xsdNsURI, "selector") + selectorNodeList, dummy, dummy = self._getXPath (inputNode, selectorXPathNode) + for selectorNode in selectorNodeList: + fieldXPathNodeList = keyrefNode.getChildrenNS(self.xsdNsURI, "field") + keyValue = [] + for fieldXPathNode in fieldXPathNodeList: + fieldChildList, attrNodeList, attrName = self._getXPath (selectorNode, fieldXPathNode, "keyref") + if len(fieldChildList) > 1: + self._addError ("The field xPath of keyref %s must evaluate to exactly 0 or 1 node!" %repr(keyRefName), fieldXPathNode) + return + + for fieldChild in fieldChildList: + if attrNodeList == []: + inputChild = fieldChild + baseTypes = self._setBaseTypes(fieldChild.getXsdNode()) + value = fieldChild.getElementValue() + else: + inputChild = attrNodeList[0] + baseTypes = self._setBaseTypes(attrNodeList[0].getXsdAttrNode(attrName)) + value = fieldChild + + if baseTypes != None: + for baseType in baseTypes: + try: + value = self._getOrderedValue (inputChild, attrName, baseType, value) + break + except SimpleTypeError, errInst: + pass + keyValue.append (value) + + keyValue = tuple(keyValue) + if keyValue != (): + if not self.xsdIdentityConstrDict[keyReference]["ValueDict"].has_key (keyValue): + self._addError ("Key reference value %s is undefined for key type %s!" %(repr(keyValue), repr(keyReference)), selectorNode) + else: + baseTypesList = self.xsdIdentityConstrDict[keyReference]["ValueDict"][keyValue] + for fieldXPathNode, baseTypes in zip(fieldXPathNodeList, baseTypesList): + fieldChildList, attrNodeList, attrName = self._getXPath (selectorNode, fieldXPathNode, "keyref") + if attrNodeList == []: + inputChild = fieldChildList[0] + refBaseTypes = self._setBaseTypes(fieldChildList[0].getXsdNode()) + else: + inputChild = attrNodeList[0] + refBaseTypes = self._setBaseTypes(inputChild.getXsdAttrNode(attrName)) + if baseTypes[0] not in refBaseTypes and refBaseTypes[0] not in baseTypes: + if baseTypes[0] != (XSD_NAMESPACE, "anyType") and refBaseTypes[0] != (XSD_NAMESPACE, "anyType"): + self._addError ("Key type and key reference type does not match (%s != %s)!" %(repr(baseTypes[0]), repr(refBaseTypes[0])), inputChild) + + + ######################################## + # check input element form + # + def _checkInputElementForm (self, xsdNode, xsdNodeNameAttr, inputNode): + targetNamespace = self._getTargetNamespace(xsdNode) + nsNameAttr = (targetNamespace, xsdNodeNameAttr) + if self.xsdElementDict.has_key(nsNameAttr) and self.xsdElementDict[nsNameAttr] == xsdNode: + elementForm = "qualified" + else: + elementForm = xsdNode.getAttributeOrDefault ("form", self._getElementFormDefault(xsdNode)) + if elementForm == "qualified": + if inputNode.getNamespaceURI() == None: + if targetNamespace != None: + self._addError ("Element %s must be qualified!" %repr(xsdNodeNameAttr), inputNode) + elif inputNode.getNamespaceURI() != targetNamespace: + self._addError ("%s undefined in specified namespace!" %repr(xsdNodeNameAttr), inputNode) + elif elementForm == "unqualified" and inputNode.getNamespaceURI() != None: + self._addError ("Local element %s must be unqualified!" %repr(xsdNodeNameAttr), inputNode) + + + ######################################## + # retrieve ordered value and base types of given typeNsName + # + def _getOrderedValue (self, inputNode, attrName, typeNsName, attrValue): + simpleTypeReturnDict = {"BaseTypes":[], "primitiveType":None} + self.simpleTypeVal.checkSimpleType (inputNode, attrName, typeNsName, attrValue, simpleTypeReturnDict, idCheck=1) + if simpleTypeReturnDict.has_key("orderedValue"): + attrValue = simpleTypeReturnDict["orderedValue"] + return attrValue + + + ######################################## + # retrieve nodes/attributes specified by given xPath + # + def _getXPath (self, node, xPathNode, identityConstraint=None): + xPath = xPathNode.getAttribute("xpath") + try: + attrIgnoreList = [(XSI_NAMESPACE, "nil")] + childList, attrNodeList, attrName = node.getXPathList (xPath, namespaceRef=xPathNode, useDefaultNs=0, attrIgnoreList=attrIgnoreList) + except Exception, errInst: + self._addError (errInst.args, node) + childList = [] + attrNodeList = [] + attrName = None + + if childList == []: + if identityConstraint == "key": + self.errorHandler.addError ("Key is missing! XPath = %s!" %repr(xPath), node) + elif identityConstraint in ("unique", "keyref"): + self.errorHandler.addWarning ("Identity constraint is missing! XPath = %s!" %repr(xPath), node) + return childList, attrNodeList, attrName + + + ######################################## + # retrieve basetypes from XML attribute (string format) + # + def _setBaseTypes (self, xsdNode): + if xsdNode.getAttribute("BaseTypes") != None: + baseTypes = string.split(xsdNode["BaseTypes"]) + baseTypeList = map (lambda basetype: NsNameTupleFactory(basetype), baseTypes) + if baseTypeList != []: + return baseTypeList + else: + return None + else: + return None + + ######################################## + # retrieve target namespace attribute for given node + # + def _getTargetNamespace(self, node): + schemaRootNode = node.getSchemaRootNode() + return schemaRootNode.getAttribute("targetNamespace") + + + ######################################## + # retrieve element form default attribute for given node + # + def _getElementFormDefault(self, node): + schemaRootNode = node.getSchemaRootNode() + return schemaRootNode.getAttributeOrDefault("elementFormDefault", "unqualified") + + ######################################## + # retrieve element form default attribute for given node + # + def _getAttributeFormDefault(self, node): + schemaRootNode = node.getSchemaRootNode() + return schemaRootNode.getAttributeOrDefault("attributeFormDefault", "unqualified") + + +######################################## +# define own exception for XML schema validation errors +# +class TagException (StandardError): + def __init__ (self, errstr="", node=None, endTag=0): + self.node = node + self.errstr = errstr + self.endTag = endTag + StandardError.__init__(self) + diff --git a/pymavlink/generator/lib/minixsv/xsvalErrorHandler.py b/pymavlink/generator/lib/minixsv/xsvalErrorHandler.py new file mode 100644 index 0000000..8ca70bb --- /dev/null +++ b/pymavlink/generator/lib/minixsv/xsvalErrorHandler.py @@ -0,0 +1,168 @@ +# +# minixsv, Release 0.9.0 +# file: xsvalErrorHandler.py +# +# XML schema validator classes +# +# history: +# 2004-09-23 rl created +# +# Copyright (c) 2004-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The minixsv XML schema validator is +# +# Copyright (c) 2004-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import string +import os + +IGNORE_WARNINGS = 0 +PRINT_WARNINGS = 1 +STOP_ON_WARNINGS = 2 + + +######################################## +# Error-Handler class for XML schema validator +# handles only validator errors, no parser errors! + +class ErrorHandler: + + def __init__(self, errorLimit, warningProc, verbose): + self.errorLimit = errorLimit + self.warningProc = warningProc + self.verbose = verbose + + self.errorList = [] + self.noOfErrors = 0 + self.warningList = [] + self.infoDict = {} + + + ######################################## + # check if errors have already been reported + + def hasErrors (self): + return self.errorList != [] + + ######################################## + # add error to errorList (raise exception only if error limit is reached) + + def addError (self, errstr, element=None, endTag=0): + filePath = "" + lineNo = 0 + if element: + filePath = element.getFilePath() + if endTag: + lineNo = element.getEndLineNumber() + else: + lineNo = element.getStartLineNumber() + self.errorList.append ((filePath, lineNo, "ERROR", "%s" %errstr)) + self.noOfErrors += 1 + if self.noOfErrors == self.errorLimit: + self._raiseXsvalException ("\nError Limit reached!!") + + + ######################################## + # add warning to warningList + + def addWarning (self, warnstr, element=None): + filePath = "" + lineNo = 0 + if element: + filePath = element.getFilePath() + lineNo = element.getStartLineNumber() + self.warningList.append ((filePath, lineNo, "WARNING", warnstr)) + + + ######################################## + # add info string to errorList + + def addInfo (self, infostr, element=None): + self.infoDict.setdefault("INFO: %s" %infostr, 1) + + + ######################################## + # add error to errorList (if given) and raise exception + + def raiseError (self, errstr, element=None): + self.addError (errstr, element) + self._raiseXsvalException () + + + ######################################## + # raise exception with complete errorList as exception string + # (only if errors occurred) + + def flushOutput (self): + if self.infoDict != {}: + print string.join (self.infoDict.keys(), "\n") + self.infoList = [] + + if self.warningProc == PRINT_WARNINGS and self.warningList != []: + print self._assembleOutputList(self.warningList, sorted=1) + self.warningList = [] + elif self.warningProc == STOP_ON_WARNINGS: + self.errorList.extend (self.warningList) + + if self.errorList != []: + self._raiseXsvalException () + + + ######################################## + # Private methods + + def _raiseXsvalException (self, additionalInfo=""): + output = self._assembleOutputList(self.errorList) + additionalInfo + self.errorList = self.warningList = [] + raise XsvalError (output) + + + def _assembleOutputList (self, outputList, sorted=0): + if sorted: + outputList.sort() + outputStrList = [] + for outElement in outputList: + outputStrList.append (self._assembleOutString(outElement)) + return string.join (outputStrList, "\n") + + + def _assembleOutString (self, listElement): + fileStr = "" + lineStr = "" + if listElement[0] != "": + if self.verbose: + fileStr = "%s: " %(listElement[0]) + else: + fileStr = "%s: " %(os.path.basename(listElement[0])) + if listElement[1] != 0: + lineStr = "line %d: " %(listElement[1]) + return "%s: %s%s%s" %(listElement[2], fileStr, lineStr, listElement[3]) + + +class XsvalError (StandardError): + pass + diff --git a/pymavlink/generator/lib/minixsv/xsvalSchema.py b/pymavlink/generator/lib/minixsv/xsvalSchema.py new file mode 100644 index 0000000..8187696 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/xsvalSchema.py @@ -0,0 +1,692 @@ +# +# minixsv, Release 0.9.0 +# file: xsvalSchema.py +# +# Derived validator class (for validation of schema files) +# +# history: +# 2004-10-07 rl created +# 2006-08-18 rl W3C testsuite passed for supported features +# 2007-05-24 rl Features for release 0.8 added, several bugs fixed +# +# Copyright (c) 2004-2008 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The minixsv XML schema validator is +# +# Copyright (c) 2004-2008 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + + +import string +import re +import os +from decimal import Decimal +from ..genxmlif.xmlifUtils import collapseString +from ..minixsv import * +from xsvalBase import XsValBase, TagException +from xsvalUtils import substituteSpecialEscChars + +_localFacetDict = {(XSD_NAMESPACE,"list"): ("length", "minLength", "maxLength", "enumeration", "pattern", "whiteSpace"), + (XSD_NAMESPACE,"union"): ("enumeration", "pattern", "whiteSpace"), + (XSD_NAMESPACE,"anySimpleType"): ("whiteSpace"),} +########################################################### +# Derived validator class for validating one input schema file against the XML rules file + +class XsValSchema (XsValBase): + + ######################################## + # overloaded validate method + # + def validate (self, inputTree, xsdTree): + XsValBase.validate(self, inputTree, xsdTree) + + self._initInternalAttributes (self.inputRoot) + self._updateLookupTables (self.inputRoot, self.xsdLookupDict) + + self._includeAndImport (self.inputTree, self.inputTree, self.xsdIncludeDict, self.xsdLookupDict) + + if not self.errorHandler.hasErrors(): + # IDs must be unique within a schema file + self.xsdIdDict = {} + + self._checkSchemaSecondLevel() + + # FIXME: Wellknown schemas are not included in the input tree although the internal attribute has been set! + # Better solution required than this workaround! + self.inputRoot["__WellknownSchemasImported__"] = "false" + + + ######################################## + # additional checks for schema files which are not covered by "xsStructs.xsd" + # + def _checkSchemaSecondLevel(self): + + targetNamespace = self.inputRoot.getAttribute("targetNamespace") + if targetNamespace == "": + self.errorHandler.raiseError("Empty string not allowed for target namespace!", self.inputRoot) + + self._checkElementNodesSecondLevel() + self._checkNotationNodesSecondLevel() + self._checkAnyNodesSecondLevel() + self._checkGroupNodesSecondLevel() + self._checkAttrGroupNodesSecondLevel() + self._checkAttributeNodesSecondLevel() + self._checkAnyAttributesSecondLevel() + + if self.errorHandler.hasErrors(): + return + + self._checkComplexTypesSecondLevel() + self._checkSimpleTypesSecondLevel() + + self._checkParticlesSecondLevel() + + self._checkIdentityConstraintsSecondLevel() + self._checkKeysSecondLevel() + self._checkKeyRefsSecondLevel() + + ######################################## + # additional checks for element nodes + # + def _checkElementNodesSecondLevel(self): + elementNodes = self.inputRoot.getElementsByTagNameNS (self.inputNsURI, "element") + for elementNode in elementNodes: + if not elementNode.hasAttribute("name") and not elementNode.hasAttribute("ref"): + self._addError ("Element must have 'name' or 'ref' attribute!", elementNode) + continue + + if elementNode.hasAttribute("ref"): + for attrName in ("name", "type", "form"): + if elementNode.hasAttribute(attrName): + self._addError ("Element with 'ref' attribute must not have %s attribute!" %repr(attrName), elementNode) + continue + + complexTypeNode = elementNode.getFirstChildNS (self.inputNsURI, "complexType") + simpleTypeNode = elementNode.getFirstChildNS (self.inputNsURI, "simpleType") + if elementNode.hasAttribute("ref") and (complexTypeNode != None or simpleTypeNode != None): + self._addError ("Element with 'ref' attribute must not have type definition!", elementNode) + continue + if elementNode.hasAttribute("type") and (complexTypeNode != None or simpleTypeNode != None): + self._addError ("Element with 'type' attribute must not have type definition!", elementNode) + continue + + if elementNode.hasAttribute("ref"): + for forbiddenAttr in ("block", "nillable", "default", "fixed"): + if elementNode.hasAttribute(forbiddenAttr): + self._addError ("Element with 'ref' attribute must not have %s attribute!" %repr(forbiddenAttr), elementNode) + + self._checkReference (elementNode, self.xsdElementDict) + + if elementNode.hasAttribute("type"): + self._checkType (elementNode, "type", self.xsdTypeDict) + + self._checkNodeId(elementNode) + self._checkOccurs (elementNode) + self._checkFixedDefault(elementNode) + + + ######################################## + # additional checks for notation nodes + # + def _checkNotationNodesSecondLevel(self): + notationNodes = self.inputRoot.getElementsByTagNameNS (self.inputNsURI, "notation") + for notationNode in notationNodes: + if not notationNode.hasAttribute("public") and not notationNode.hasAttribute("system"): + self._addError ("Notation must have 'public' or 'system' attribute!", notationNode) + + + ######################################## + # additional checks for anyNodes + # + def _checkAnyNodesSecondLevel(self): + anyNodes = self.inputRoot.getElementsByTagNameNS (self.inputNsURI, "any") + for anyNode in anyNodes: + self._checkOccurs (anyNode) + # check for unique ID + self._checkNodeId (anyNode) + + + ######################################## + # additional checks for group nodes + # + def _checkGroupNodesSecondLevel(self): + groupNodes = self.inputRoot.getElementsByTagNameNS (self.inputNsURI, "group") + for groupNode in groupNodes: + self._checkNodeId(groupNode) + if groupNode.hasAttribute("ref"): + self._checkReference (groupNode, self.xsdGroupDict) + self._checkOccurs (groupNode) + if self.errorHandler.hasErrors(): + return +# for groupNode in groupNodes: +# if groupNode.hasAttribute("name"): +# self._checkGroupNodeCircularDef(groupNode, {groupNode["name"]:1}) + + def _checkGroupNodeCircularDef(self, groupNode, groupNameDict): + childGroupsRefNodes, dummy, dummy = groupNode.getXPathList (".//%sgroup" %(self.inputNsPrefixString)) + for childGroupRefNode in childGroupsRefNodes: + if childGroupRefNode.hasAttribute("ref"): + childGroupNode = self.xsdGroupDict[childGroupRefNode.getQNameAttribute("ref")] + if not groupNameDict.has_key(childGroupNode["name"]): + groupNameDict[childGroupNode["name"]] = 1 + self._checkGroupNodeCircularDef(childGroupNode, groupNameDict) + else: + self._addError ("Circular definition of group %s!" %repr(childGroupNode["name"]), childGroupNode) + + + ######################################## + # additional checks for attributeGroup nodes + # + def _checkAttrGroupNodesSecondLevel(self): + attributeGroupNodes = self.inputRoot.getElementsByTagNameNS (self.inputNsURI, "attributeGroup") + for attributeGroupNode in attributeGroupNodes: + if attributeGroupNode.hasAttribute("ref"): + self._checkReference (attributeGroupNode, self.xsdAttrGroupDict) + + self._checkNodeId(attributeGroupNode) + + ######################################## + # additional checks for attribute nodes + # + def _checkAttributeNodesSecondLevel(self): + attributeNodes = self.inputRoot.getElementsByTagNameNS (XSD_NAMESPACE, "attribute") + for attributeNode in attributeNodes: + if os.path.basename(attributeNode.getFilePath()) != "XMLSchema-instance.xsd": + # global attributes must always be "qualified" + if (attributeNode.getParentNode() == self.inputRoot or + self._getAttributeFormDefault(attributeNode) == "qualified"): + if self._getTargetNamespace(attributeNode) == XSI_NAMESPACE: + self._addError ("Target namespace of an attribute must not match '%s'!" %XSI_NAMESPACE, attributeNode) + + if not attributeNode.hasAttribute("name") and not attributeNode.hasAttribute("ref"): + self._addError ("Attribute must have 'name' or 'ref' attribute!", attributeNode) + continue + + if attributeNode.getAttribute("name") == "xmlns": + self._addError ("Attribute must not match 'xmlns'!", attributeNode) + + if attributeNode.hasAttribute("ref"): + if attributeNode.hasAttribute("name"): + self._addError ("Attribute may have 'name' OR 'ref' attribute!", attributeNode) + if attributeNode.hasAttribute("type"): + self._addError ("Attribute may have 'type' OR 'ref' attribute!", attributeNode) + if attributeNode.hasAttribute("form"): + self._addError ("Attribute 'form' is not allowed in this context!", attributeNode) + + if attributeNode.getFirstChildNS(XSD_NAMESPACE, "simpleType") != None: + self._addError ("Attribute may only have 'ref' attribute OR 'simpleType' child!", attributeNode) + + self._checkReference (attributeNode, self.xsdAttributeDict) + + if attributeNode.hasAttribute("type"): + if attributeNode.getFirstChildNS(XSD_NAMESPACE, "simpleType") != None: + self._addError ("Attribute may only have 'type' attribute OR 'simpleType' child!", attributeNode) + + self._checkType (attributeNode, "type", self.xsdTypeDict, (XSD_NAMESPACE, "simpleType")) + + use = attributeNode.getAttribute("use") + if use in ("required", "prohibited") and attributeNode.hasAttribute("default"): + self._addError ("Attribute 'default' is not allowed, because 'use' is '%s'!" %(use), attributeNode) + + self._checkNodeId(attributeNode, unambiguousPerFile=0) + + self._checkFixedDefault(attributeNode) + + + ######################################## + # additional checks for attribute wildcards + # + def _checkAnyAttributesSecondLevel(self): + anyAttributeNodes, dummy, dummy = self.inputRoot.getXPathList (".//%sanyAttribute" %(self.inputNsPrefixString)) + for anyAttributeNode in anyAttributeNodes: + # check for unique ID + self._checkNodeId (anyAttributeNode) + + + ######################################## + # additional checks for complex types + # + def _checkComplexTypesSecondLevel(self): + prefix = self.inputNsPrefixString + contentNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)scomplexContent/%(prefix)srestriction | .//%(prefix)scomplexContent/%(prefix)sextension" % vars()) + for contentNode in contentNodes: + self._checkType(contentNode, "base", self.xsdTypeDict, (XSD_NAMESPACE, "complexType")) + + contentNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)ssimpleContent/%(prefix)srestriction | .//%(prefix)ssimpleContent/%(prefix)sextension" % vars()) + for contentNode in contentNodes: + baseNsName = contentNode.getQNameAttribute("base") + if baseNsName != (XSD_NAMESPACE, "anyType"): + typeNsName = contentNode.getParentNode().getNsName() + self._checkBaseType(contentNode, baseNsName, self.xsdTypeDict, typeNsName) + else: + self._addError ("Referred type must not be 'anyType'!", contentNode) + # check for unique ID + self._checkNodeId (contentNode) + + complexTypeNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)scomplexType | .//%(prefix)sextension" % vars()) + for complexTypeNode in complexTypeNodes: + validAttrDict = {} + # check for duplicate attributes + self._updateAttributeDict (complexTypeNode, validAttrDict, 1) + # check for duplicate ID attributes + idAttrNode = None + for key, val in validAttrDict.items(): + attrType = val["RefNode"].getQNameAttribute("type") + if attrType == (XSD_NAMESPACE, "ID"): + if not idAttrNode: + idAttrNode = val["Node"] + else: + # TODO: check also if attribute has a type which is derived from ID! + self._addError ("Two attribute declarations of complex type are IDs!", val["Node"]) + + # check for unique ID + self._checkNodeId (complexTypeNode) + + contentNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)scomplexType/%(prefix)s*" % vars()) + for contentNode in contentNodes: + self._checkOccurs (contentNode) + + contentNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)scomplexContent | .//%(prefix)ssimpleContent" % vars()) + for contentNode in contentNodes: + # check for unique ID + self._checkNodeId (contentNode) + + + ######################################## + # additional checks for simple types + # + def _checkParticlesSecondLevel(self): + prefix = self.inputNsPrefixString + # check for duplicate element names + particleNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)sall | .//%(prefix)schoice | .//%(prefix)ssequence" % vars()) + for particleNode in particleNodes: + elementTypeDict = {} + elementNameDict = {} + groupNameDict = {} + self._checkContainedElements (particleNode, particleNode.getLocalName(), elementNameDict, elementTypeDict, groupNameDict) + self._checkOccurs (particleNode) + # check for unique ID + self._checkNodeId (particleNode) + + + def _checkContainedElements (self, node, particleType, elementNameDict, elementTypeDict, groupNameDict): + prefix = self.inputNsPrefixString + for childNode in node.getChildren(): + childParticleType = childNode.getLocalName() + if childParticleType in ("sequence", "choice", "all"): + dummy = {} + self._checkContainedElements (childNode, childParticleType, dummy, elementTypeDict, groupNameDict) + elif childParticleType in ("group"): + if childNode["ref"] != None: + childGroupNode = self.xsdGroupDict[childNode.getQNameAttribute("ref")] + if not groupNameDict.has_key(childGroupNode["name"]): + groupNameDict[childGroupNode["name"]] = 1 + for cChildNode in childGroupNode.getChildren(): + if cChildNode.getLocalName() != "annotation": + self._checkContainedElements (cChildNode, particleType, elementNameDict, elementTypeDict, groupNameDict) + else: + self._addError ("Circular definition of group %s!" %repr(childGroupNode["name"]), childNode) + else: + for cChildNode in childNode.getChildren(): + if cChildNode.getLocalName() != "annotation": + self._checkContainedElements (cChildNode, particleType, elementNameDict, elementTypeDict, groupNameDict) + else: + if childNode.getLocalName() == "any": + elementName = childNode.getAttribute("namespace") + else: + elementName = childNode.getAttributeOrDefault("name", childNode.getAttribute("ref")) + + if childNode.hasAttribute("type"): + if not elementTypeDict.has_key(elementName): + elementTypeDict[elementName] = childNode["type"] + elif childNode["type"] != elementTypeDict[elementName]: + self._addError ("Element %s has identical name and different types within %s!" %(repr(elementName), repr(particleType)), childNode) + if particleType != "sequence": + if not elementNameDict.has_key(elementName): + elementNameDict[elementName] = 1 + else: + self._addError ("Element %s is not unique within %s!" %(repr(elementName), repr(particleType)), childNode) + + + ######################################## + # additional checks for simple types + # + def _checkSimpleTypesSecondLevel(self): + prefix = self.inputNsPrefixString + + simpleTypeNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)ssimpleType" % vars()) + for simpleTypeNode in simpleTypeNodes: + # check for unique ID + self._checkNodeId (simpleTypeNode) + + restrictionNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)ssimpleType/%(prefix)srestriction" % vars()) + for restrictionNode in restrictionNodes: + + # check for unique ID + self._checkNodeId (restrictionNode) + + if not restrictionNode.hasAttribute("base") and restrictionNode.getFirstChildNS (self.inputNsURI, "simpleType") == None: + self._addError ("Simple type restriction must have 'base' attribute or 'simpleType' child tag!", restrictionNode) + + if restrictionNode.hasAttribute("base") and restrictionNode.getFirstChildNS (self.inputNsURI, "simpleType") != None: + self._addError ("Simple type restriction must not have 'base' attribute and 'simpleType' child tag!", restrictionNode) + + if restrictionNode.hasAttribute("base"): + self._checkType(restrictionNode, "base", self.xsdTypeDict) + + minExcl = restrictionNode.getFirstChildNS(self.inputNsURI, "minExclusive") + minIncl = restrictionNode.getFirstChildNS(self.inputNsURI, "minInclusive") + if minExcl != None and minIncl != None: + self._addError ("Restriction attributes 'minExclusive' and 'minInclusive' cannot be defined together!", restrictionNode) + maxExcl = restrictionNode.getFirstChildNS(self.inputNsURI, "maxExclusive") + maxIncl = restrictionNode.getFirstChildNS(self.inputNsURI, "maxInclusive") + if maxExcl != None and maxIncl != None: + self._addError ("Restriction attributes 'maxExclusive' and 'maxInclusive' cannot be defined together!", restrictionNode) + + # check facets of associated primitive type + for restrictionNode in restrictionNodes: + try: + if restrictionNode.hasAttribute("base"): + facetNsName = self._getFacetType (restrictionNode, [restrictionNode.getParentNode(),], self.xsdTypeDict) + if not facetNsName: + continue + if _localFacetDict.has_key(facetNsName): + suppFacets = _localFacetDict[facetNsName] + else: + suppFacets, dummy, dummy = self.xsdTypeDict[facetNsName].getXPathList (".//hfp:hasFacet/@name" % vars()) + + specifiedFacets = {"length":None, "minLength":None, "maxLength":None, + "minExclusive":None, "minInclusive":None, "maxExclusive":None, "maxInclusive":None, + "totalDigits": None, "fractionDigits":None} + for childNode in restrictionNode.getChildren(): + if childNode.getLocalName() in suppFacets: + if specifiedFacets.has_key(childNode.getLocalName()): + specifiedFacets[childNode.getLocalName()] = childNode["value"] + facetElementNode = self.xsdElementDict[childNode.getNsName()] + try: + self._checkElementTag (facetElementNode, restrictionNode, (childNode,), 0) + except TagException, errInst: + self._addError (errInst.errstr, errInst.node, errInst.endTag) + if childNode.getLocalName() in ("enumeration", "minExclusive", "minInclusive", "maxExclusive", "maxInclusive"): + simpleTypeReturnDict = self._checkSimpleType (restrictionNode, "base", childNode, "value", childNode["value"], None, checkAttribute=1) + if simpleTypeReturnDict != None and simpleTypeReturnDict.has_key("orderedValue"): + if childNode.getLocalName() != "enumeration": + specifiedFacets[childNode.getLocalName()] = simpleTypeReturnDict["orderedValue"] + elif childNode.getLocalName() == "enumeration": + self._checkSimpleType (restrictionNode, "base", childNode, "value", childNode["value"], None, checkAttribute=1) + elif childNode.getLocalName() != "annotation": + self._addError ("Facet %s not allowed for base type %s!" %(childNode.getLocalName(), repr(restrictionNode["base"])), childNode) + if specifiedFacets["length"] != None: + if specifiedFacets["minLength"] != None or specifiedFacets["maxLength"] != None: + self._addError ("Facet 'minLength' and 'maxLength' not allowed if facet 'length' is specified!", restrictionNode) + else: + if specifiedFacets["maxLength"] != None and specifiedFacets["minLength"] != None: + if int(specifiedFacets["maxLength"]) < int(specifiedFacets["minLength"]): + self._addError ("Facet 'maxLength' < facet 'minLength'!", restrictionNode) + + if specifiedFacets["totalDigits"] != None and specifiedFacets["fractionDigits"] != None: + if int(specifiedFacets["totalDigits"]) < int(specifiedFacets["fractionDigits"]): + self._addError ("Facet 'totalDigits' must be >= 'fractionDigits'!", restrictionNode) + + if specifiedFacets["minExclusive"] != None and specifiedFacets["minInclusive"] != None: + self._addError ("Facets 'minExclusive' and 'minInclusive' are mutually exclusive!", restrictionNode) + if specifiedFacets["maxExclusive"] != None and specifiedFacets["maxInclusive"] != None: + self._addError ("Facets 'maxExclusive' and 'maxInclusive' are mutually exclusive!", restrictionNode) + + minValue = specifiedFacets["minExclusive"] + if specifiedFacets["minInclusive"] != None: + minValue = specifiedFacets["minInclusive"] + maxValue = specifiedFacets["maxExclusive"] + if specifiedFacets["maxInclusive"] != None: + maxValue = specifiedFacets["maxInclusive"] + # TODO: use orderedValue for '<' check!! + if minValue != None and maxValue != None and maxValue < minValue: + self._addError ("maxValue facet < minValue facet!", restrictionNode) + + except TagException: + self._addError ("Primitive type for base type not found!", restrictionNode) + + listNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)slist" % vars()) + for listNode in listNodes: + # check for unique ID + self._checkNodeId (listNode) + + if not listNode.hasAttribute("itemType") and listNode.getFirstChildNS (self.inputNsURI, "simpleType") == None: + self._addError ("List type must have 'itemType' attribute or 'simpleType' child tag!", listNode) + elif listNode.hasAttribute("itemType") and listNode.getFirstChildNS (self.inputNsURI, "simpleType") != None: + self._addError ("List type must not have 'itemType' attribute and 'simpleType' child tag!", listNode) + elif listNode.hasAttribute("itemType"): + itemType = self._checkType(listNode, "itemType", self.xsdTypeDict) + if self.xsdTypeDict.has_key(itemType): + if self.xsdTypeDict[itemType].getLocalName() != "simpleType": + self._addError ("ItemType %s must be a simple type!" %(repr(itemType)), listNode) + elif self.xsdTypeDict[itemType].getFirstChild().getLocalName() == "list": + self._addError ("ItemType %s must not be a list type!" %(repr(itemType)), listNode) + + unionNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)ssimpleType/%(prefix)sunion" % vars()) + for unionNode in unionNodes: + # check for unique ID + self._checkNodeId (unionNode) + + if not unionNode.hasAttribute("memberTypes"): + for childNode in unionNode.getChildren(): + if childNode.getLocalName() != "annotation": + break + else: + self._addError ("Union must not be empty!", unionNode) + else: + for memberType in string.split(unionNode["memberTypes"]): + memberNsName = unionNode.qName2NsName(memberType, 1) + self._checkBaseType(unionNode, memberNsName, self.xsdTypeDict) + if self.xsdTypeDict.has_key(memberNsName): + if self.xsdTypeDict[memberNsName].getLocalName() != "simpleType": + self._addError ("MemberType %s must be a simple type!" %(repr(memberNsName)), unionNode) + + patternNodes, dummy, dummy = self.inputRoot.getXPathList (".//%(prefix)spattern" % vars()) + for patternNode in patternNodes: + pattern = patternNode["value"] + try: + pattern = substituteSpecialEscChars (pattern) + try: + test = re.compile(pattern) + except Exception, errstr: + self._addError (str(errstr), patternNode) + self._addError ("%s is not a valid regular expression!" %(repr(patternNode["value"])), patternNode) + except SyntaxError, errInst: + self._addError (repr(errInst[0]), patternNode) + + + ######################################## + # additional checks for keyrefs + # + def _checkIdentityConstraintsSecondLevel(self): + identityConstraintNodes, dummy, dummy = self.inputRoot.getXPathList (".//%sunique" %(self.inputNsPrefixString)) + for identityConstraintNode in identityConstraintNodes: + # check for unique ID + self._checkNodeId (identityConstraintNode) + + selectorNode = identityConstraintNode.getFirstChildNS(XSD_NAMESPACE, "selector") + self._checkNodeId (selectorNode) + try: + completeChildList, attrNodeList, attrNsNameFirst = identityConstraintNode.getParentNode().getXPathList (selectorNode["xpath"], selectorNode) + if attrNsNameFirst != None: + self._addError ("Selection of attributes is not allowed for selector!", selectorNode) + except Exception, errstr: + self._addError (errstr, selectorNode) + + try: + fieldNode = identityConstraintNode.getFirstChildNS(XSD_NAMESPACE, "field") + identityConstraintNode.getParentNode().getXPathList (fieldNode["xpath"], fieldNode) + self._checkNodeId (fieldNode) + except Exception, errstr: + self._addError (errstr, fieldNode) + + + ######################################## + # additional checks for keyrefs + # + def _checkKeysSecondLevel(self): + keyNodes, dummy, dummy = self.inputRoot.getXPathList (".//%skey" %(self.inputNsPrefixString)) + for keyNode in keyNodes: + # check for unique ID + self._checkNodeId (keyNode) + + fieldNode = keyNode.getFirstChildNS(XSD_NAMESPACE, "field") + if fieldNode != None: + self._checkNodeId (fieldNode) + + + ######################################## + # additional checks for keyrefs + # + def _checkKeyRefsSecondLevel(self): + keyrefNodes, dummy, dummy = self.inputRoot.getXPathList (".//%skeyref" %(self.inputNsPrefixString)) + for keyrefNode in keyrefNodes: + # check for unique ID + self._checkNodeId (keyrefNode) + + self._checkKeyRef(keyrefNode, self.xsdIdentityConstrDict) + + + ######################################## + # helper methods + # + + def _checkFixedDefault(self, node): + if node.hasAttribute("default") and node.hasAttribute("fixed"): + self._addError ("%s may have 'default' OR 'fixed' attribute!" %repr(node.getLocalName()), node) + if node.hasAttribute("default"): + self._checkSimpleType (node, "type", node, "default", node["default"], None, checkAttribute=1) + if node.hasAttribute("fixed"): + self._checkSimpleType (node, "type", node, "fixed", node["fixed"], None, checkAttribute=1) + + + def _checkReference(self, node, dict): + baseNsName = node.getQNameAttribute("ref") + if dict.has_key(baseNsName): + refNode = dict[baseNsName] + fixedValue = node.getAttribute("fixed") + fixedRefValue = refNode.getAttribute("fixed") + if fixedValue != None and fixedRefValue != None and fixedValue != fixedRefValue: + self._addError ("Fixed value %s of attribute does not match fixed value %s of reference!" %(repr(fixedValue), repr(fixedRefValue)), node) + + else: + self._addError ("Reference %s not found!" %(repr(baseNsName)), node) + + def _checkType(self, node, typeAttrName, dict, typeNsName=None): + baseNsName = node.getQNameAttribute(typeAttrName) + self._checkBaseType(node, baseNsName, dict, typeNsName) + return baseNsName + + def _checkBaseType(self, node, baseNsName, dict, typeNsName=None): + if not dict.has_key(baseNsName) and baseNsName != (XSD_NAMESPACE, "anySimpleType"): + self._addError ("Definition of type %s not found!" %(repr(baseNsName)), node) + elif typeNsName != None: + if typeNsName == (XSD_NAMESPACE, "simpleContent"): + if node.getNsName() == (XSD_NAMESPACE, "restriction"): + if (baseNsName != (XSD_NAMESPACE, "anySimpleType") and + dict[baseNsName].getNsName() == (XSD_NAMESPACE, "complexType") and + dict[baseNsName].getFirstChild().getNsName() == typeNsName): + pass + else: + self._addError ("Referred type %s must be a complex type with simple content!" %(repr(baseNsName)), node) + else: # extension + if (baseNsName == (XSD_NAMESPACE, "anySimpleType") or + dict[baseNsName].getNsName() == (XSD_NAMESPACE, "simpleType") or + (dict[baseNsName].getNsName() == (XSD_NAMESPACE, "complexType") and + dict[baseNsName].getFirstChild().getNsName() == typeNsName)): + pass + else: + self._addError ("Referred type %s must be a simple type or a complex type with simple content!" %(repr(baseNsName)), node) + else: + if typeNsName == (XSD_NAMESPACE, "simpleType") and baseNsName == (XSD_NAMESPACE, "anySimpleType"): + pass + elif dict[baseNsName].getNsName() != typeNsName: + self._addError ("Referred type %s must be a %s!" %(repr(baseNsName), repr(typeNsName)), node) + + + def _checkKeyRef(self, keyrefNode, dict): + baseNsName = keyrefNode.getQNameAttribute("refer") + if not dict.has_key(baseNsName): + self._addError ("keyref refers unknown key %s!" %(repr(baseNsName)), keyrefNode) + else: + keyNode = dict[baseNsName]["Node"] + if keyNode.getNsName() not in ((XSD_NAMESPACE, "key"), (XSD_NAMESPACE, "unique")): + self._addError ("reference to non-key constraint %s!" %(repr(baseNsName)), keyrefNode) + if len(keyrefNode.getChildrenNS(XSD_NAMESPACE, "field")) != len(keyNode.getChildrenNS(XSD_NAMESPACE, "field")): + self._addError ("key/keyref field size mismatch!", keyrefNode) + + + def _checkOccurs (self, node): + minOccurs = node.getAttributeOrDefault("minOccurs", "1") + maxOccurs = node.getAttributeOrDefault("maxOccurs", "1") + if maxOccurs != "unbounded": + if string.atoi(minOccurs) > string.atoi(maxOccurs): + self._addError ("Attribute minOccurs > maxOccurs!", node) + + + def _checkNodeId (self, node, unambiguousPerFile=1): + if node.hasAttribute("id"): + # id must only be unambiguous within one file + if unambiguousPerFile: + nodeId = (node.getAbsUrl(), collapseString(node["id"])) + else: + nodeId = collapseString(node["id"]) + if not self.xsdIdDict.has_key(nodeId): + self.xsdIdDict[nodeId] = node + else: + self._addError ("There are multiple occurences of ID value %s!" %repr(nodeId), node) + + + def _getFacetType(self, node, parentNodeList, xsdTypeDict): + baseNsName = node.getQNameAttribute("base") + try: + baseNode = xsdTypeDict[baseNsName] + except: + self._addError ("Base type %s must be an atomic simple type definition or a builtin type!" %repr(baseNsName), node) + return None + + if baseNode in parentNodeList: + self._addError ("Circular type definition (type is contained in its own type hierarchy)!", node) + return None + + if baseNode.getNsName() == (XSD_NAMESPACE, "simpleType"): + if baseNode.getAttribute("facetType") != None: + facetType = baseNode.qName2NsName(baseNode["facetType"], 1) + node.getParentNode()["facetType"] = node.nsName2QName(facetType) + return facetType + else: + for baseNodeType in ("list", "union"): + if baseNode.getFirstChildNS (XSD_NAMESPACE, baseNodeType) != None: + return (XSD_NAMESPACE, baseNodeType) + else: + parentNodeList.append(node) + return self._getFacetType(baseNode.getFirstChildNS(XSD_NAMESPACE, "restriction"), parentNodeList, xsdTypeDict) + else: + self._addError ("Base type %s must be an atomic simple type definition or a builtin type!" %repr(baseNsName), node) + return None + + diff --git a/pymavlink/generator/lib/minixsv/xsvalSimpleTypes.py b/pymavlink/generator/lib/minixsv/xsvalSimpleTypes.py new file mode 100644 index 0000000..5476234 --- /dev/null +++ b/pymavlink/generator/lib/minixsv/xsvalSimpleTypes.py @@ -0,0 +1,704 @@ +# +# minixsv, Release 0.9.0 +# file: xsvalSimpleTypes.py +# +# class for validation of XML schema simple types +# +# history: +# 2004-09-09 rl created +# 2006-08-18 rl W3C testsuite passed for supported features +# 2007-05-24 rl Features for release 0.8 added, some bugs fixed +# +# Copyright (c) 2004-2007 by Roland Leuthe. All rights reserved. +# +# -------------------------------------------------------------------- +# The minixsv XML schema validator is +# +# Copyright (c) 2004-2007 by Roland Leuthe +# +# By obtaining, using, and/or copying this software and/or its +# associated documentation, you agree that you have read, understood, +# and will comply with the following terms and conditions: +# +# Permission to use, copy, modify, and distribute this software and +# its associated documentation for any purpose and without fee is +# hereby granted, provided that the above copyright notice appears in +# all copies, and that both that copyright notice and this permission +# notice appear in supporting documentation, and that the name of +# the author not be used in advertising or publicity +# pertaining to distribution of the software without specific, written +# prior permission. +# +# THE AUTHOR DISCLAIMS ALL WARRANTIES WITH REGARD +# TO THIS SOFTWARE, INCLUDING ALL IMPLIED WARRANTIES OF MERCHANT- +# ABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR +# BE LIABLE FOR ANY SPECIAL, INDIRECT OR CONSEQUENTIAL DAMAGES OR ANY +# DAMAGES WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, +# WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS +# ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE +# OF THIS SOFTWARE. +# -------------------------------------------------------------------- + +import sys +import string +import re +import datetime +from decimal import Decimal +from ..genxmlif.xmlifUtils import removeWhitespaces, collapseString, normalizeString, NsNameTupleFactory +from ..minixsv import XSD_NAMESPACE +from xsvalUtils import substituteSpecialEscChars + +################################################### +# Validator class for simple types +################################################### +class XsSimpleTypeVal: + + def __init__ (self, parent): + self.parent = parent + self.xmlIf = parent.xmlIf + self.xsdNsURI = parent.xsdNsURI + self.xsdIdDict = parent.xsdIdDict + self.xsdIdRefDict = parent.xsdIdRefDict + + + def unlink (self): + self.parent = None + + + ######################################## + # validate given value against simpleType + # + def checkSimpleType (self, inputNode, attrName, typeName, attributeValue, returnDict, idCheck): + returnDict["adaptedAttrValue"] = attributeValue + returnDict["BaseTypes"].append(str(typeName)) + if _suppBaseTypeDict.has_key(typeName): + try: + _suppBaseTypeDict[typeName] (inputNode, typeName, attributeValue, returnDict) + returnDict["primitiveType"] = typeName + except BaseTypeError, errstr: + raise SimpleTypeError("Value of %s (%s) %s" %(repr(attrName), repr(attributeValue), errstr)) + + elif self.parent.xsdTypeDict.has_key(typeName): + typedefNode = self.parent.xsdTypeDict[typeName] + if typedefNode.getNsName() == (XSD_NAMESPACE, "simpleType"): + self.checkSimpleTypeDef (inputNode, typedefNode, attrName, attributeValue, returnDict, idCheck) + elif (typedefNode.getNsName() == (XSD_NAMESPACE, "complexType") and + typedefNode.getFirstChild().getNsName() == (XSD_NAMESPACE, "simpleContent")): + self.checkSimpleTypeDef (inputNode, typedefNode.getFirstChild(), attrName, attributeValue, returnDict, idCheck) + elif typedefNode.getAttribute("mixed") == "true": + self.checkSimpleType (inputNode, attrName, (XSD_NAMESPACE, "string"), attributeValue, returnDict, idCheck) + elif typeName != (XSD_NAMESPACE, "anyType"): + raise SimpleTypeError("Attribute %s requires a simple type!" %repr(attrName)) + + if idCheck: + adaptedAttrValue = returnDict["adaptedAttrValue"] + if typeName == (XSD_NAMESPACE, "ID"): + if not self.xsdIdDict.has_key(adaptedAttrValue): + self.xsdIdDict[adaptedAttrValue] = inputNode + else: + raise SimpleTypeError("There are multiple occurences of ID value %s!" %repr(adaptedAttrValue)) + if typeName == (XSD_NAMESPACE, "IDREF"): + self.xsdIdRefDict[adaptedAttrValue] = inputNode + else: + # TODO: Fehler im XSD-File => Check muss an anderer Stelle erfolgen + raise SimpleTypeError("%s uses unknown type %s!" %(repr(attrName), repr(typeName))) + + + ######################################## + # validate given value against simpleType node + # + def checkSimpleTypeDef (self, inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck): + returnDict["adaptedAttrValue"] = attributeValue + restrictionElement = xsdElement.getFirstChildNS(self.xsdNsURI, "restriction") + extensionElement = xsdElement.getFirstChildNS(self.xsdNsURI, "extension") + listElement = xsdElement.getFirstChildNS(self.xsdNsURI, "list") + unionElement = xsdElement.getFirstChildNS(self.xsdNsURI, "union") + if restrictionElement != None: + self._checkRestrictionTag (inputNode, restrictionElement, attrName, attributeValue, returnDict, idCheck) + if extensionElement != None: + self._checkExtensionTag (inputNode, extensionElement, attrName, attributeValue, returnDict, idCheck) + elif listElement != None: + self._checkListTag (inputNode, listElement, attrName, attributeValue, returnDict, idCheck) + elif unionElement != None: + self._checkUnionTag (inputNode, unionElement, attrName, attributeValue, returnDict, idCheck) + + + ######################################## + # validate given value against base type + # + def checkBaseType (self, inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck): + baseType = xsdElement.getQNameAttribute("base") + if baseType != NsNameTupleFactory(None): + self.checkSimpleType (inputNode, attrName, baseType, attributeValue, returnDict, idCheck) + else: + baseTypeNode = xsdElement.getFirstChildNS(self.xsdNsURI, "simpleType") + self.checkSimpleTypeDef (inputNode, baseTypeNode, attrName, attributeValue, returnDict, idCheck) + + + ######################################## + # validate given value against restriction node + # + def _checkRestrictionTag (self, inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck): + savedAttrValue = attributeValue + # first check against base type + self.checkBaseType (inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck) + + minExcl = xsdElement.getFirstChildNS(self.xsdNsURI, "minExclusive") + minIncl = xsdElement.getFirstChildNS(self.xsdNsURI, "minInclusive") + maxExcl = xsdElement.getFirstChildNS(self.xsdNsURI, "maxExclusive") + maxIncl = xsdElement.getFirstChildNS(self.xsdNsURI, "maxInclusive") + + if minExcl != None: + minExclReturnDict = {"BaseTypes":[], "primitiveType":None} + minExclValue = minExcl.getAttribute("value") + self.checkBaseType (inputNode, xsdElement, attrName, minExclValue, minExclReturnDict, idCheck=0) + if returnDict.has_key("orderedValue") and minExclReturnDict.has_key("orderedValue"): + if returnDict["orderedValue"] <= minExclReturnDict["orderedValue"]: + raise SimpleTypeError ("Value of %s (%s) is <= minExclusive (%s)" %(repr(attrName), repr(attributeValue), repr(minExclValue))) + elif minIncl != None: + minInclReturnDict = {"BaseTypes":[], "primitiveType":None} + minInclValue = minIncl.getAttribute("value") + self.checkBaseType (inputNode, xsdElement, attrName, minInclValue, minInclReturnDict, idCheck=0) + if returnDict.has_key("orderedValue") and minInclReturnDict.has_key("orderedValue"): + if returnDict["orderedValue"] < minInclReturnDict["orderedValue"]: + raise SimpleTypeError ("Value of %s (%s) is < minInclusive (%s)" %(repr(attrName), repr(attributeValue), repr(minInclValue))) + if maxExcl != None: + maxExclReturnDict = {"BaseTypes":[], "primitiveType":None} + maxExclValue = maxExcl.getAttribute("value") + self.checkBaseType (inputNode, xsdElement, attrName, maxExclValue, maxExclReturnDict, idCheck=0) + if returnDict.has_key("orderedValue") and maxExclReturnDict.has_key("orderedValue"): + if returnDict["orderedValue"] >= maxExclReturnDict["orderedValue"]: + raise SimpleTypeError ("Value of %s (%s) is >= maxExclusive (%s)" %(repr(attrName), repr(attributeValue), repr(maxExclValue))) + elif maxIncl != None: + maxInclReturnDict = {"BaseTypes":[], "primitiveType":None} + maxInclValue = maxIncl.getAttribute("value") + self.checkBaseType (inputNode, xsdElement, attrName, maxInclValue, maxInclReturnDict, idCheck=0) + if returnDict.has_key("orderedValue") and maxInclReturnDict.has_key("orderedValue"): + if returnDict["orderedValue"] > maxInclReturnDict["orderedValue"]: + raise SimpleTypeError ("Value of %s (%s) is > maxInclusive (%s)" %(repr(attrName), repr(attributeValue), repr(maxInclValue))) + + totalDigitsNode = xsdElement.getFirstChildNS(self.xsdNsURI, "totalDigits") + if totalDigitsNode != None: + orderedValueStr = repr(returnDict["orderedValue"]) + digits = re.findall("\d" ,orderedValueStr) + if digits[0] == "0" and len(digits) > 1: + digits = digits[1:] + totalDigitsValue = totalDigitsNode.getAttribute("value") + if totalDigitsNode.getAttribute("fixed") == "true": + if len(digits) != string.atoi(totalDigitsValue): + raise SimpleTypeError ("Total number of digits != %s for %s (%s)" %(repr(totalDigitsValue), repr(attrName), repr(attributeValue))) + else: + if len(digits) > string.atoi(totalDigitsValue): + raise SimpleTypeError ("Total number of digits > %s for %s (%s)" %(repr(totalDigitsValue), repr(attrName), repr(attributeValue))) + + fractionDigitsNode = xsdElement.getFirstChildNS(self.xsdNsURI, "fractionDigits") + if fractionDigitsNode != None: + orderedValueStr = repr(returnDict["orderedValue"]) + fractionDigitsValue = fractionDigitsNode.getAttribute("value") + result = re.search("(?P\d*)(?P\.)(?P\d+)", orderedValueStr) + if result != None: + numberOfFracDigits = len (result.group('fracDigits')) + else: + numberOfFracDigits = 0 + if fractionDigitsNode.getAttribute("fixed") == "true" and numberOfFracDigits != string.atoi(fractionDigitsValue): + raise SimpleTypeError ("Fraction number of digits != %s for %s (%s)" %(repr(fractionDigitsValue), repr(attrName), repr(attributeValue))) + elif numberOfFracDigits > string.atoi(fractionDigitsValue): + raise SimpleTypeError ("Fraction number of digits > %s for %s (%s)" %(repr(fractionDigitsValue), repr(attrName), repr(attributeValue))) + + if returnDict.has_key("length"): + lengthNode = xsdElement.getFirstChildNS(self.xsdNsURI, "length") + if lengthNode != None: + length = string.atoi(lengthNode.getAttribute("value")) + if returnDict["length"] != length: + raise SimpleTypeError ("Length of %s (%s) must be %d!" %(repr(attrName), repr(attributeValue), length)) + minLengthNode = xsdElement.getFirstChildNS(self.xsdNsURI, "minLength") + if minLengthNode != None: + minLength = string.atoi(minLengthNode.getAttribute("value")) + if returnDict["length"] < minLength: + raise SimpleTypeError ("Length of %s (%s) must be >= %d!" %(repr(attrName), repr(attributeValue), minLength)) + maxLengthNode = xsdElement.getFirstChildNS(self.xsdNsURI, "maxLength") + if maxLengthNode != None: + maxLength = string.atoi(maxLengthNode.getAttribute("value")) + if returnDict["length"] > maxLength: + raise SimpleTypeError ("Length of %s (%s) must be <= %d!" %(repr(attrName), repr(attributeValue), maxLength)) + + whiteSpace = xsdElement.getFirstChildNS(self.xsdNsURI, "whiteSpace") + if whiteSpace != None: + returnDict["wsAction"] = whiteSpace.getAttribute("value") + if returnDict["wsAction"] == "replace": + normalizedValue = normalizeString(attributeValue) + if normalizedValue != attributeValue: + returnDict["adaptedAttrValue"] = normalizedValue + elif returnDict["wsAction"] == "collapse": + collapsedValue = collapseString(attributeValue) + if collapsedValue != attributeValue: + returnDict["adaptedAttrValue"] = collapsedValue + + enumerationElementList = xsdElement.getChildrenNS(self.xsdNsURI, "enumeration") + if enumerationElementList != []: + if returnDict.has_key("orderedValue"): + attributeValue = returnDict["orderedValue"] + elif returnDict.has_key("adaptedAttrValue"): + attributeValue = returnDict["adaptedAttrValue"] + + for enumeration in enumerationElementList: + enumReturnDict = {"BaseTypes":[], "primitiveType":None} + enumValue = enumeration["value"] + self.checkBaseType (inputNode, xsdElement, attrName, enumValue, enumReturnDict, idCheck=0) + if enumReturnDict.has_key("orderedValue"): + enumValue = enumReturnDict["orderedValue"] + elif enumReturnDict.has_key("adaptedAttrValue"): + enumValue = enumReturnDict["adaptedAttrValue"] + + if enumValue == attributeValue: + break + else: + raise SimpleTypeError ("Enumeration value %s not allowed!" %repr(attributeValue)) + + + if returnDict.has_key("adaptedAttrValue"): + attributeValue = returnDict["adaptedAttrValue"] + + patternMatch = 1 + notMatchedPatternList = [] + for patternNode in xsdElement.getChildrenNS(self.xsdNsURI, "pattern"): + rePattern = patternNode.getAttribute("value") + intRePattern = rePattern + try: + intRePattern = substituteSpecialEscChars (intRePattern) + except SyntaxError, errInst: + raise SimpleTypeError, str(errInst) + patternMatch = self._matchesPattern (intRePattern, attributeValue) + + if patternMatch: + break + else: + notMatchedPatternList.append(rePattern) + + if not patternMatch: + try: + pattern = " nor ".join(notMatchedPatternList) + except: + pattern = "" + raise SimpleTypeError ("Value of attribute %s (%s) does not match pattern %s!" %(repr(attrName), repr(attributeValue), repr(pattern))) + + + ######################################## + # checks if 'value' matches 'rePattern' completely + # + def _matchesPattern (self, intRePattern, attributeValue): + completePatternMatch = 0 + try: + regexObj = re.match(intRePattern, attributeValue, re.U) + if regexObj and regexObj.end() == len(attributeValue): + completePatternMatch = 1 + except Exception: + pass + return completePatternMatch + + + ######################################## + # validate given value against list node + # + def _checkListTag (self, inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck): + if attributeValue != "": + itemType = xsdElement.getQNameAttribute ("itemType") + # substitute multiple whitespace characters by a single ' ' + collapsedValue = collapseString(attributeValue) + returnDict["wsAction"] = "collapse" + returnDict["adaptedAttrValue"] = collapsedValue + + # divide up attributeValue => store it into list + attributeList = string.split(collapsedValue, " ") + for attrValue in attributeList: + elementReturnDict = {"BaseTypes":[], "primitiveType":None} + if itemType != (None, None): + self.checkSimpleType (inputNode, attrName, itemType, attrValue, elementReturnDict, idCheck) + else: + itemTypeNode = xsdElement.getFirstChildNS(self.xsdNsURI, "simpleType") + self.checkSimpleTypeDef (inputNode, itemTypeNode, attrName, attrValue, elementReturnDict, idCheck) + + returnDict["BaseTypes"].extend(elementReturnDict["BaseTypes"]) + returnDict["length"] = len(attributeList) + else: + returnDict["length"] = 0 + + + ######################################## + # validate given value against extension node + # + def _checkExtensionTag (self, inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck): + # first check against base type + self.checkBaseType (inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck) + + + ######################################## + # validate given value against union node + # + def _checkUnionTag (self, inputNode, xsdElement, attrName, attributeValue, returnDict, idCheck): + memberTypes = xsdElement.getAttribute ("memberTypes") + if memberTypes != None: + # substitute multiple whitespace characters by a single ' ' + # divide up attributeValue => store it into list + for memberType in string.split(collapseString(memberTypes), " "): + try: + self.checkSimpleType (inputNode, attrName, xsdElement.qName2NsName(memberType, useDefaultNs=1), attributeValue, returnDict, idCheck) + return + except SimpleTypeError, errstr: + pass + + # memberTypes and additional type definitions is legal! + for childSimpleType in xsdElement.getChildrenNS(self.xsdNsURI, "simpleType"): + try: + self.checkSimpleTypeDef (inputNode, childSimpleType, attrName, attributeValue, returnDict, idCheck) + return + except SimpleTypeError, errstr: + pass + + raise SimpleTypeError ("%s (%s) is no valid union member type!" %(repr(attrName), repr(attributeValue))) + + +############################################################### +# Base type check functions +############################################################### + +reDecimal = re.compile("[+-]?[0-9]*\.?[0-9]+", re.U) +reInteger = re.compile("[+-]?[0-9]+", re.U) +reDouble = re.compile("([+-]?[0-9]*\.?[0-9]+([eE][+\-]?[0-9]+)?)|INF|-INF|NaN", re.U) +reHexBinary = re.compile("([a-fA-F0-9]{2})*", re.U) +reBase64Binary = re.compile("(?P[a-zA-Z0-9+/]*)={0,3}", re.U) +reQName = re.compile(substituteSpecialEscChars("\i\c*"), re.U) +reDuration = re.compile("-?P(?P\d+Y)?(?P\d+M)?(?P\d+D)?(T(?P\d+H)?(?P\d+M)?((?P\d+)(?P\.\d+)?S)?)?", re.U) + +reDateTime = re.compile("(?P\d{4}-\d{2}-\d{2})T(?P